home castoo
chapitre electronique
Electronique outils

PTZ CAMERA PELCO D
Le source C++

Octobre 2025

Projet PTZ"
  1. Description générale du projet PTZ.
  2. Le materiel necessaire au montage.
  3. Le câblage.
  4. La gestion de Pelco et du Wifi.
  5. Les fichiers STL.
  6. Le code C++
Platine camera PTZ PELCO WIFI

Le code C++ du projet.

Généralités

Tout commence par une initialisation de la position. Les deux moteurs partent dans une recherche du point marqué par les fins de course. Pour le balancier la recherche est rapide, pour la rotation horizontale c'est plus long ! Cette grande roue assure une démultiplication afin d'avoir des déplacements fluide de la caméra ceci implique un bon délai pour atteindre les extrêmes. Une fois la position des fins de course déterminée on va se positionner à une position intermédiaire qui sera reconnu dans le programme comme point zéro. Ensuite on envoi la page HTML, Le programme se positionne alors en attente en Wifi au cas où une commande arrive de la page HTML et sur la liaison série au cas où une commande arrive depuis une caméra par Pelco D. En cas de réception d'une commande après décodage elle est transmise au moteur pas à pas qui assure le déplacement voulu.

Ce code est une base, il est très facile d'ajouter des fonctions pour une gestion du pelco beaucoup plus large, ajouter des possibilité de décodage de déplacement en diagonale, ou la mémorisation de positions prédéfinies... Améliorer la prise en compte de la commande de changement de vitesse de déplacement. Prévoir le décodage d'autres protocoles de déplacement.
...

Les librairies utilisées

AccelStepper.h Cette librairie est très utilisée, elle permet la gestion des moteurs pas à pas avec une grande facilité et efficacité. Dans notre cas elle nous permet des déplacements fluides en gérant des accélérations progressives. Les principales fonctions utilisées dans ce projet sont les déplacements en relatif, le repérage de la position en cours. Il est à noter que la librairie prend en compte les changements de direction, le numéro de la broche "DIR" étant disponible au moment de la déclaration de la librairie. Il faut donc passer les ordres de déplacement en valeurs positives ou négatives.

ESP8266WiFi.h, ESPAsyncTCP.h, ESPAsyncWebServer.h La librairie ESP8266WiFi est des plus communes, elle est utilisée dans tous les projets Wifi avec un esp8266. Par contre les deux suivantes sont beaucoup moins connues (j'avoue que sans mon collègue "chatgpt" je ne connaissait pas leur existence !). J'avais pour habitude d'utiliser "ESP8266WebServer.h" mais dans le cas de ce projet comme il était nécessaire, de gérer en simultané l'interface série et l'interface Wifi. Avec la librairie standard, j'avais des loupés, voir des plantages. L'utilisation de ces librairie "Asynchrone" était la bonne solution !

Le code source C++




/*
Gestion PTZ camera
Site castoo.fr
Decembre 2025
Décodage des trames PELCO D
Commande HTML WiFi
Ce source est un logiciel libre.
Vous pouvez la redistribuer et ou le modifier.
Ce source est distribué dans l'espoir qu'il sera utile,
mais SANS AUCUNE GARANTIE, sans même la garantie implicite de
QUALITÉ MARCHANDE ou ADÉQUATION À UN USAGE PARTICULIER. 
Merci de mentionner le site castoo.fr si vous réutilisez ce code.
Pour utiliser ce programme modifier le SSID et le mot de passe de la box lignes 15 et 16
Connectez vous sur l'adresse IP inscrite dans le code du setup (192.168.1.102) dans cet bexemple.
*/

#include <Arduino.h>
#include <ESP8266WiFi.h>
#include <ESPAsyncTCP.h>
#include <ESPAsyncWebServer.h>
#include "AccelStepper.h"
// #define debug_sur_usb

#define ssid "XXXXXXXXXXXXXXXX" // SSID de la box
#define password "YYYYYYYYYYYYYYYYYYY" // Pass de la box

#define STEPX D2 // moteur X pas
#define DIRX D1  // moteur X dir
#define LIMX D7  // moteur X Limite

#define STEPY D6 // moteur Y pas
#define DIRY D5  // moteur Y dir
#define LIMY D3  // moteur Y Limite

#define ENAB_MOT D4  // enable des 2 moteurs (attention d4 est utilisé par le boot etat haut)

AccelStepper moteur_X(AccelStepper::DRIVER, STEPX, DIRX);
AccelStepper moteur_Y(AccelStepper::DRIVER, STEPY, DIRY);

const int nb_pa_tour = 2048;

AsyncWebServer server(80); // Port IP par defaut du serveur HTML

long max_x = (8 * nb_pa_tour)-10; // max axe X 
long max_y = 800; // max axe Y)
long min_x = -max_x; // Valeur max de decalage en x du point zero
long min_y = -2200; // Valeur max de decalage en y du point zero
long pas_mouv = 100; // Pas mouvement de base (nb tour moteur)
long memo_x = 0; // Mémo positions x
long memo_y = 0; // Mémo positions y
long median_x = 8 * nb_pa_tour; // position x camera de face (ofset depuis le point 0) une fois init terminé = 0
long median_y = 1000; // position y camera de face hauteur de niveau plat (ofset depuis le point 0) une fois init terminé = 0

String pos_cam = ""; // Commande gestion mouvement camera
bool depl_rapide = false; // Accelerateur vitesse de déplacement
byte buffer[7]; // Trame Pelco-D
int indexBuf = 0;
char lastFrame[32] = "Aucune trame reçue";
unsigned long frameCount = 0; // Nb de frame qui nous sont vraiment utiles (les droite, gauche, haut et bas)

byte checksum(byte *cmd) {
 byte sum = 0;
 for(int i=1;i<5;i++) sum+=cmd[i];
 return sum % 256;
}

// Construction de la page HTML
String Page_html(){
  String b_0, b_1, b_2, b_3, b_4;
  if (pos_cam == "↹") { b_0 = "checked"; }
  if (pos_cam == "⬆") { b_1 = "checked"; }
  if (pos_cam == "⬇") { b_2 = "checked"; }
  if (pos_cam == "⬅") { b_3 = "checked"; }
  if (pos_cam == "⮕") { b_4 = "checked"; }
  //String page = "<!DOCTYPE html><html dir='ltr' lang='fr'><head><meta http-equiv='content-type' content='text/html; charset=UTF-8'>";
  String page = "<!DOCTYPE html><html dir='ltr' lang='fr'><head><meta http-equiv='refresh'; content='1'; charset='UTF-8'>";
  page += "<title>Gestion support de camera</title>";
  page += "<style> body { background-color: grey; font-family: Sans-Serif; Color: orange; }</style>";
  page += "</head><body><div align='center'><h1>Gestion du support de caméra</h1>";
  page += "<form action='/commande' method='get'><INPUT type='submit' name='vit_rap' value='";
  if(depl_rapide) page += "lente"; else  page += "rapide"; page += "' />";
  if(depl_rapide) page += "Vitesse de déplacement lente."; else  page += "Vitesse de déplacement rapide.";
  page += "</div><table align='center'>";
  page += "<tr><td colspan='3'></td></tr><tr><td colspan='3'></td></tr><td colspan='3'></td></tr></tr><td colspan='3'></td></tr>";
  page += "<tr><td align='center' width='100'></td><td align='center' width='100'><INPUT type='submit' name='direction' value='⬆' " + b_1 + " /></td><td align='center' width='100'></td></tr>";
  page += "<tr><td colspan='3'></td></tr><tr><td colspan='3'></td></tr><td colspan='3'></td></tr></tr><td colspan='3'></td></tr>";
  page += "<tr><td align='center' width='100'><INPUT type='submit' name='direction' value='⬅' " + b_3 + " /></td><td align='center' width='100'><INPUT type='submit' name='direction' value='↹' " + b_0;
  page += " /></td><td align='center' width='100'><INPUT type='submit' name='direction' value='⮕' " + b_4 + " /></td></tr>";
  page += "<tr><td colspan='3'></td></tr><tr><td colspan='3'></td></tr><td colspan='3'></td></tr></tr><td colspan='3'></td></tr>";
  page += "<tr><td align='center' width='100'></td><td align='center' width='100'><INPUT type='submit' name='direction' value='⬇' " + b_2 + " /></td><td align='center' width='100'></td></tr>";
  page += "<tr><td colspan='3'></td></tr><tr><td colspan='3'></td></tr><td colspan='3'></td></tr>";
  page += "</table>";
  page += "<p align='center'>Pos. Vert. : " + String(memo_y) + " Pos. Hor. : " + String(memo_x) + "</p>";
  page += "<p align='center'>Min_x : " + String(min_x) + " Max_x : " + String(max_x) + "</p>";
  page += "<p align='center'>Min_y : " + String(min_y) + " Max_y : " + String(max_y) + "</p><br/><br/><div align='center'><h1>Pelco D</h1></div>";
  page += "<p align='center'><b>Nb de trame : </b>" + String(frameCount) +"</p>";
  page += "<p align='center'>B0 : " + String(buffer[0]) + " B1 : " + String(buffer[1]) + " B2 : " + String(buffer[2]) + " B3 : " + String(buffer[3]) + " B4 : " + String(buffer[4]) + " B5 : " + String(buffer[5]) + " B6 : " + String(buffer[6]) + "</p></body></html>";
  return page;
}

<br/>
<div class='cad_code'>
<pre>
<code>
// Gere les deplacements de la caméra
void modif_pos_moteur(){
  long pos = 0;
  digitalWrite(ENAB_MOT, LOW); // Ouverture commandes sur les 2 moteurs
  if(pos_cam == &quot;↹&quot;) { // Retour en position initiale
      moteur_Y.runToNewPosition(0);
      memo_y = pos;
      moteur_X.runToNewPosition(0);
      memo_x = pos;
  } else if(pos_cam == &quot;⬆&quot;) { // vers le haut
    if(depl_rapide) pos = memo_y + (pas_mouv * 5); else pos = memo_y + pas_mouv;
    if(pos &lt;= max_y){
      moteur_Y.runToNewPosition(pos);
      memo_y = pos;
    }
  } else if(pos_cam == &quot;⬇&quot;) { // vers le bas
    if(depl_rapide) pos = memo_y - (pas_mouv * 5); else pos = memo_y - pas_mouv;
    if(pos &gt;= min_y){
      moteur_Y.runToNewPosition(pos);
      memo_y = pos;
    }
  } else if(pos_cam == &quot;⬅&quot;) { // vers la gauche
    if(depl_rapide) pos = memo_x - (pas_mouv * 5); else pos = memo_x - pas_mouv;
    if(pos &gt;= min_x){
      moteur_X.runToNewPosition(pos);
      memo_x = pos;
    }
  } else if(pos_cam == &quot;⮕&quot;) { // vers la droite
    if(depl_rapide) pos = memo_x + (pas_mouv * 5); else pos = memo_x + pas_mouv;
    if(pos &lt;= max_x){
      moteur_X.runToNewPosition(pos);
      memo_x = pos;
    }
  }
  digitalWrite(ENAB_MOT, HIGH); // Fermeture commandes sur les 2 moteurs
  pos_cam = &quot;0&quot;;
}

// Gestion du dialogue avec la page HTML
void Gestion_Page(AsyncWebServerRequest *request) {
  String result = &quot;&quot;;
  if ( request-&gt;hasParam(&quot;vit_rap&quot;) ) { if(request-&gt;getParam(&quot;vit_rap&quot;)-&gt;value()==&quot;rapide&quot;) depl_rapide=true; else  depl_rapide=false; }
  if (request-&gt;hasParam(&quot;direction&quot;)) { String direction = request-&gt;getParam(&quot;direction&quot;)-&gt;value(); pos_cam = direction; }
  request-&gt;redirect(&quot;/&quot;);
}

// Fonction pour décoder Pelco-D et piloter moteurs pas-à-pas
void Decode_Pelco(){
  long pos = 0;
  byte cmd2 = buffer[2];
  byte X_Vit = buffer[3];
  byte Y_Vit = buffer[4];
  digitalWrite(ENAB_MOT, LOW); // Ouverture commandes sur les 2 moteurs
  if(cmd2 == 0x04){ // Horizontal Gauche
    if(X_Vit &gt; 30) pos = memo_x - (pas_mouv * 5); else pos = memo_x - pas_mouv;
    if(pos &gt;= min_x){
      moteur_X.runToNewPosition(pos);
      memo_x = pos;
    }
  }
  if(cmd2 == 0x02){ // Horizontal Droite
    if(X_Vit &gt; 30) pos = memo_x + (pas_mouv * 5); else pos = memo_x + pas_mouv;
    if(pos &lt;= max_x){
      moteur_X.runToNewPosition(pos);
      memo_x = pos;
    }
  }
  if(cmd2 == 0x08){ // Vertical Haut
    if(Y_Vit &gt; 30) pos = memo_y + (pas_mouv * 5); else pos = memo_y + pas_mouv;
    if(pos &lt;= max_y){
      moteur_Y.runToNewPosition(pos);
      memo_y = pos;
    }
  }
  if(cmd2 == 0x10){ // Vertical Bas
    if(Y_Vit &gt; 30) pos = memo_y - (pas_mouv * 5); else pos = memo_y - pas_mouv;
    if(pos &gt;= min_y){
      moteur_Y.runToNewPosition(pos);
      memo_y = pos;
    }
  }
  digitalWrite(ENAB_MOT, HIGH); // Fermeture commandes sur les 2 moteurs
}

// Lecture Pelco D
void Li_Pelco() {
 while (Serial.available()) {
   uint8_t b = Serial.read();
   if (indexBuf == 0){ if (b != 0xFF) continue; } // Synchronisation sur 0xFF
   if (indexBuf == 2){ if (!(b == 0x02 or b == 0x04 or b == 0x08 or b == 0x10)) continue; }
   buffer[indexBuf++] = b;
   if (indexBuf == 7) { // Quand trame complète
    indexBuf = 0;
    if (checksum(buffer) == buffer[5]){ // Si checksum ok
       frameCount++;
       Decode_Pelco(); // On decode
    }
   }
 }
}

// Recherche position 0
void init_zero(){
  #ifdef debug_sur_usb
    Serial.println(&quot;Fonction init_zero&quot;);
  #endif
  digitalWrite(ENAB_MOT, LOW); // Ouverture commandes sur les 2 moteurs
  moteur_X.setMaxSpeed(800.0);
  moteur_X.setAcceleration(100.0);
  moteur_X.moveTo(20*nb_pa_tour);
  moteur_Y.setMaxSpeed(200.0);
  moteur_Y.setAcceleration(100.0);
  moteur_Y.moveTo(10*(nb_pa_tour));
  bool init_ok = false;
  bool def_x = false;
  bool def_y = false;
  while ( ! init_ok){
    #ifdef debug_sur_usb
      Serial.println(&quot;boucle init_ok&quot;);
    #endif
    if(! digitalRead(LIMX)){
      #ifdef debug_sur_usb
        Serial.println(&quot;boucle LIMX&quot;);
      #endif
      memo_x = moteur_X.currentPosition();
      def_x = true;
    }
    if(! digitalRead(LIMY)){
      #ifdef debug_sur_usb
        Serial.println(&quot;boucle LIMY&quot;);
      #endif
      def_y = true;
      memo_y = moteur_Y.currentPosition();
    }
    if(def_x &amp;&amp; def_y){
      init_ok = true;
    }else{ 
      if( ! def_x) moteur_X.run();
      if( ! def_y) moteur_Y.run();
      delay(2);
    }
  }
  #ifdef debug_sur_usb
    Serial.println(&quot;Fin reperage limites : &quot;);
    Serial.println(&quot;LIMX = &quot; + String(memo_x));
    Serial.println(&quot;LIMY = &quot; + String(memo_y));
    Serial.println(&quot;Remise a 0 des points aux limites : &quot;);
  #endif
  moteur_X.setCurrentPosition(0);
  moteur_Y.setCurrentPosition(0);
  #ifdef debug_sur_usb
    Serial.println(&quot;RAZ LIMX = &quot; + String(moteur_X.currentPosition()));
    Serial.println(&quot;RAZ LIMY = &quot; + String(moteur_Y.currentPosition()));
  #endif
  moteur_X.move(-median_x);
  moteur_Y.move(-median_y);
  #ifdef debug_sur_usb
    Serial.println(&quot;Centrage : &quot;);
  #endif
  init_ok = false;
  def_x = false;
  def_y = false;
  while ( ! init_ok){
  	#ifdef debug_sur_usb
      Serial.println(&quot;pos X = &quot; + String(moteur_X.currentPosition()));
      Serial.println(&quot;pos Y = &quot; + String(moteur_Y.currentPosition()));
    #endif
    if(moteur_X.currentPosition() == -median_x){
      memo_x = moteur_X.currentPosition();
      def_x = true;
    }
    if(moteur_Y.currentPosition() == -median_y){
      def_y = true;
      memo_y = moteur_Y.currentPosition();
    }
    if(def_x &amp;&amp; def_y){
      init_ok = true;
    }else{ 
      if( ! def_x) moteur_X.run();
      if( ! def_y) moteur_Y.run();
      delay(2);
    }
  }
  moteur_X.setCurrentPosition(0);
  moteur_Y.setCurrentPosition(0);
  median_x = 0; memo_x = median_x;
  median_y = 0; memo_y = median_y;
	#ifdef debug_sur_usb
    Serial.println(&quot;LIMX = &quot; + String(memo_x));
    Serial.println(&quot;LIMY = &quot; + String(memo_y));
    Serial.println(&quot;Fin fonction init_zero : &quot;);
  #endif
  digitalWrite(ENAB_MOT, HIGH); // Fermeture commandes sur les 2 moteurs
}

void setup(){
  #ifndef debug_sur_usb
    Serial.setDebugOutput(false);
    Serial.begin(9600, SERIAL_8N1); // vitesse Pelco D
  #endif
	#ifdef debug_sur_usb
    Serial.begin(115200); // vitesse debug
    Serial.println(&quot;Entree Setup&quot;);
    Serial.println();
  #endif
  delay(500);
  pinMode(LIMX, INPUT);
  pinMode(LIMY, INPUT);
  pinMode(ENAB_MOT, OUTPUT); // attention utilise par boot esp
  #ifdef debug_sur_usb
    Serial.println(&quot;Serveur OK  Lancement recherche limites moteurs.&quot;);
  #endif
  init_zero();
	#ifdef debug_sur_usb
    Serial.println(&quot;Cnx Wifi &quot;);
    Serial.println(&quot;Adresse IP fixe : 192.168.1.89 &quot;);
  #endif
  IPAddress ip(192, 168, 1, 89); // Declaration adr IP fixe
  IPAddress dns(192,168,1,254);
  IPAddress gateway(192,168,1,254);
  IPAddress subnet(255, 255, 255, 0);
  WiFi.config(ip, dns, gateway, subnet);
  WiFi.begin ( ssid, password );
  while ( WiFi.status() != WL_CONNECTED ){
    delay ( 500 );
    #ifdef debug_sur_usb
      Serial.print(&quot;.&quot;);
    #endif
  }
  #ifdef debug_sur_usb
    Serial.println(&quot;Wifi OK  Lancement serveur web.&quot;);
  #endif
  server.on(&quot;/&quot;, HTTP_GET, [](AsyncWebServerRequest *request){
    request-&gt;send(200, &quot;text/html&quot;, Page_html());
  }); 
  server.on ( &quot;/commande&quot;,  HTTP_GET, Gestion_Page );
  server.begin();
  #ifdef debug_sur_usb
    Serial.println(&quot;Fin du Setup.&quot;);
  #endif
}

void loop() {
  Li_Pelco(); // Lecture trame Pelco D
  if(pos_cam != &quot;0&quot;)  modif_pos_moteur();
  yield();
}




Haut de page
accueil electronique

Bricolage Robotique Informatique Peinture Voyage
Téléc. portail Le robot "mécano" Astuces informatique Henri Bertrou Auvergne
Bat. Iphone 6S Le robot "solaire" Réseau couche app. Jean-Michel Castille Floride
Robot piscine Servo et IR" Réseau Les couches New York
Xiaomi M365 Le robot "thymio" Réseaux Outils L'Ouest américain
Mac Mini Le robot "Rovio" Unités grandeur inf. L'Ile Maurice
Putty SSH Windows L'Italie / Venise
Bases Raspberry Tunisie
Termius IPhone/IPad Grece
Le vieux ZX 81
...
Navigation La Rochelle CNC / Imp3D Electronique Programmation
Rencontre dauphins Les Minimes Construction CNC Alim. TPL 5110 Doc. programme
Analyse NMEA 0183 Le Vieux port CNC du commerce Carte ESP8266 Indent programme
graph. NMEA 0183 L'Ile de Ré Martyr CNC ESP8266 1 relai Prog. objet
Analyse trames AIS A visiter Réa. imp. 3D ESP8266 Alarme Prog. procédurale
Analyse AIS TCP-IP Cura impression 3D ESP8266 MQTT
Sortie en ketch Plateau CR10 ESP8266 Temp.
Echange GPS C80 Anémomètre.
HP Sun-Odyssey CNC / 3D en vrac MCP9808 Librairie
LCD yanmar Saisie Oled
Testeur nmea esp1 i2c