KonradIT / goprowifihack

Unofficial GoPro WiFi API Documentation - HTTP GET requests for commands, status, livestreaming and media query.
Apache License 2.0
2.12k stars 335 forks source link

Gopro 8 UDP Cam-Commands #177

Open Kowal666666 opened 4 years ago

Kowal666666 commented 4 years ago

I have some Cam-commands found on google, but it's not complete and some are not working. I can turn on the cammera, like remote do (even when it is turn off), commend for shutter on, works but it is like a button, give it one it will start REC, give the command one again and REC is off. The change mode don't work.

//--------------------- Cam-Commands ---------------------------------------------------------------------- uint8_t PW0[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x50, 0x57, 0x00}; // power off uint8_t SH1[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x53, 0x48, 0x01}; // shutter 1 uint8_t SH0[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x53, 0x48, 0x00}; // shutter 0 uint8_t CM0[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x43, 0x4D, 0x01}; // change mode <- not working uint8_t wt[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x77, 0x74}; // wait uint8_t pw[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x70, 0x77}; // hold power on uint8_t st[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x73, 0x74}; // status? uint8_t cv[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x63, 0x76}; // cam version uint8_t OO[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x4F, 0x4F}; // UNKNOWN uint8_t se[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x73, 0x65}; // UNKNOWN uint8_t lc[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x6C, 0x63}; // Display image

Do somebody have complete list of command at UDP port, to simulatr the Smart Remote?

KonradIT commented 4 years ago

Interesting, how did you get these to work and emulate the smart remote? I tried a while ago to setup a ESP8266 to spawn an AP called HERO-RC-XXXX and send commands, but could not get it to work, only pairing.

Kowal666666 commented 4 years ago

Sorry, i forgot the source. https://github.com/sepp89117/GoPro-Multiple-Smart-Remote-ESP8266 I use this as first steps, modified the scetch and going on with some tests. Easiest way would be to turn on camera as AP with UDP pocket (it's working) and switch the arduino to Client and use normal 10.5.5.9 commands as http, but gopro 8 don't turn on the wifi AP, before connecting with gorpo App on smartphone, so http commands/urls has no use for me. I need udp simple commands to operate the gopro, ang project sepp89117 is good direction with gopro 8. I don't know how to scan udp packets from remote, to fully simulate it.

Kowal666666 commented 4 years ago

Tricky thing is, that gopro wifi works like a shit sometimes. Generally i switch the AP on and off, give the connect remote on gopro, and after couple of probes it finally catch the ESP8266 as remote.

Kowal666666 commented 4 years ago

Ok, i found something like this. https://github.com/cepoon/GoProRemote It is what i needed,

Kowal666666 commented 4 years ago

Interesting, how did you get these to work and emulate the smart remote? I tried a while ago to setup a ESP8266 to spawn an AP called HERO-RC-XXXX and send commands, but could not get it to work, only pairing.

My code, it's working, gopro wakeup in light sleep, but if it is powwered off for longer time it must be powered on by hand. Sorry the code is a little messy, but it's working. I've tried to use hardware serial, but i don't now why it wont receive - it's just sending. Neverless software serial works good. Sometimes ESP8266 is reseting by himself, but i've done it not to interrupt recording if it's on. Values for channel 14 and 8 i'm using to 'communicate' with frysky telemetry passthrough to lua script on X-lite.

include

include

include

include "mavlink_types.h"

include "common/mavlink.h"

//--------------------- set MAC for NodeMCU 1.0 (ESP-12E) with 2.5.2 core --------------------------------- uint8_t ap_mac[] = {0x84, 0xF3, 0xEB, 0x46, 0x0C, 0x1E};// MAC-Adsress of my Smart-Remote extern "C" void preinit() {

include "user_interface.h"

wifi_set_opmode(SOFTAP_MODE); wifi_set_macaddr(SOFTAP_IF, ap_mac); } //--------------------- heart beat declarations ----------------------------------------------------------- uint8_t stdMsg[] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; unsigned int rateI = 1; // durable counter 1 unsigned int rate2 = 1; // durable counter 2 unsigned int rate3 = 0; // durable counter 3 //--------------------- GoPro MAC declarations ------------------------------------------------------------ //uint8_t M1BSSID[] = {0x11, 0x22, 0x33, 0x44, 0x55, 0x66}; //Mac gopro IPAddress M1IP(0, 0, 0, 0); //--------------------- Cam-Commands ---------------------------------------------------------------------- uint8_t st[] = {'s', 't'};//status uint8_t se[] = {'s', 'e'};//session info uint8_t SH[] = {'S', 'H'}; uint8_t CM[] = {'C', 'M'}; //na stdMsg[13]= 0:'video',1:'photo',2:'burst', 3:'timelapse photo', 7:'settings' uint8_t cm[] = {'c', 'm'};//camera mode info uint8_t PW0[] = {'P', 'W', 0x00};//Power off uint8_t PV[] = {'P', 'V'}; // preview uint8_t pw[] = {'p', 'w'}; // hold power on uint8_t wt[] = {'w', 't'}; // wait, send in the network //--------------------- other declarations ---------------------------------------------------------------- const unsigned int plocalPort = 8383; // Port der Fernbedienung const unsigned int cremotePort = 8484; // Port der Kamera const unsigned int wifiChannel = 1; // Channel of my Smart-Remote = 1 const char ssid_pilot = "HERO-RC-460C1E";//HERO-RC-E423DD"; // SSID of my Smart-Remote "HERO-RC-A1111425435131" struct station_info stat_info; byte packetBuffer[64]; // buffer to hold incoming and outgoing packets unsigned long millis_old = 0; IPAddress ip(10, 71, 79, 1); // IP of my Smart-Remote IPAddress gateway(10, 71, 79, 1); // GW of my Smart-Remote IPAddress subnet(255, 255, 255, 0); // SM of my Smart-Remote //---------------------GOPRO declarations --------------------------- boolean gopro_present = true; char gopro_mode = 9; //0-video or liveburst, 1-photo or night, 2-burst, 3-timelapse photo char gopro_rec = 0; char gopro_time_min = 0; char gopro_time_sec = 0; unsigned long millis_gopro = 0; char gopro_restart = 0; //----------------------Mavlink------------------------------------------------- HardwareSerial DebugSerial = Serial;//(14,12); //RX-12, TX-14 SoftwareSerial MavSerial(15,13);

boolean dron_heartbeat = false; unsigned long millis_command = 0; unsigned long millis_mavlink_receive = 0; int dron_status=0, dron_status_old=0; int dron_ch8=1; //channel to override - status of gopro int dron_ch14=0, dron_ch14_old=0; //channel to get commands for gopro from telemetry RC - special functions int dron_alt=0; int dron_angle=0;

//--------------------- instances ------------------------------------------------------------------------- WiFiUDP Udp;

define LED 2 //Pin 2 for LED onboard

boolean LedStatus = false;

define LedHeartBeat 16

define LedGopro 14

define LedMavlink 12

//--------------------- program ---------------------------------------------------------------------------

void setup() { WiFi.disconnect(true); WiFi.softAPdisconnect(true); WiFi.mode(WIFI_AP); // Set WiFi in AP mode WiFi.hostname(ssid_pilot);//ESP_E423DD"); // Hostname of my Smart-Remote //-------------- DEBUD ------------------- // DebugSerial.begin(115200); //serial monitor connected to software serial pin 12/5 // DebugSerial.println("Software DEBUG Serial on PIN 14-D6/TX Started"); pinMode(LED, OUTPUT); pinMode(LedHeartBeat, OUTPUT); pinMode(LedGopro, OUTPUT); pinMode(LedMavlink, OUTPUT); digitalWrite(LED, HIGH); // Turn the LED on digitalWrite(LedHeartBeat, HIGH); // Turn the LED on digitalWrite(LedGopro, HIGH); // Turn the LED on digitalWrite(LedMavlink, HIGH); // Turn the LED on MavSerial.begin(115200); //PixHawk connected to hardware serial delay(5000); GoproStartCam(); //run gopro if (gopro_present == true) { MavLink_receive(); MavLink_request_datastream(); //run Mavlink } if (gopro_rec > 0) //If Arduino Restarted, and gopro recording, do not change and stop recording in first main loop() { if (gopro_mode == 3) {dron_ch14_old = 1596; dron_ch14 = 1596;}
if (gopro_mode == 0) {dron_ch14_old = 1545; dron_ch14 = 1545;}
}

}

void loop() { if(dron_heartbeat == false) { if (millis() - millis_mavlink_receive > 1) {MavLink_receive();} if (millis() - millis_command > 3000) {MavLink_request_datastream();} //reset Mavlink } if (gopro_present == true and dron_heartbeat == true) { if (millis() - millis_mavlink_receive > 1) {MavLink_receive();} if (dron_ch14 != dron_ch14_old) { if (dron_ch14 == 1545) //start video { GoproShutterStop(); delay(3000); stdMsg[11] = CM[0]; stdMsg[12] = CM[1]; stdMsg[13] = 0x00; // video GoproSendReq(stdMsg, 14); delay(2000); GoproReciveReq(); GoproHeartBeat(); delay(1000); GoproShutterStart();
} // if (dron_ch14 == 1596) //start burst // { // GoproShutterStop(); // delay(3000); // stdMsg[11] = CM[0]; // stdMsg[12] = CM[1]; // stdMsg[13] = 0x02; // burst // GoproSendReq(stdMsg, 14); // delay(2000); // GoproReciveReq(); // GoproHeartBeat(); // delay(1000); // GoproShutterStart();
// } if (dron_ch14 == 1596) //start timelapse photo { GoproShutterStop(); delay(3000); stdMsg[11] = CM[0]; stdMsg[12] = CM[1]; stdMsg[13] = 0x03; // burst GoproSendReq(stdMsg, 14); delay(2000); GoproReciveReq(); GoproHeartBeat(); delay(1000); GoproShutterStart();
} dron_ch14_old = dron_ch14; } if (millis() - millis_gopro > 1000) { LedStatus = !LedStatus; if (LedStatus == false) {digitalWrite(LED, LOW);digitalWrite(LedHeartBeat, LOW);} if (LedStatus == true) {digitalWrite(LED, HIGH);digitalWrite(LedHeartBeat, HIGH);} GoproReadSession(); millis_gopro = millis(); if (gopro_mode == 3) {dron_ch8 = 100 + (gopro_rec 50);} //Time Lapse mode 100/150rec if (gopro_mode == 2) {dron_ch8 = 200 + (gopro_rec 50);} //Burst mode 200/250rec if (gopro_mode == 1) {dron_ch8 = 300 + (gopro_rec 50);} //Photo mode 300/350rec if (gopro_mode == 0) //video 1000+600min+10sec { dron_ch8 = 1000; if (gopro_rec == 1) dron_ch8 = dron_ch8 + 100 + 10gopro_time_min60 + 10gopro_time_sec; } Mavlink_CH8_override(dron_ch8); } } if (gopro_present == false) {delay(5000);} //wait 1min and do nothing, after while will be Hardware Reset - and good

}

void GoproStartCam() { GoproStartAP(); millis_old = millis(); while (M1IP[0] == 0 and gopro_present==true) { GoproClientStatus(); // stdMsg[11] = wt[0]; // stdMsg[12] = wt[1]; // sendReq(stdMsg, 13); GoproHeartBeat(); delay(500); if (millis() - millis_old > 10000) { GoproStopAP(); delay(200); GoproStartAP(); millis_old = millis(); } if (millis() - millis_old > 180000) {gopro_present = false; GoproStopAP();} //if gopro not present in 3min switch off WiFi do nothing } if (gopro_present == true) { while (packetBuffer[13]!=0) {GoproReciveReq();} //buffer cleaning dron_ch8 = 20; //Gopro present OK for FrSky GoproReciveReq(); GoproHeartBeat(); delay(1000); gopro_restart = 0; digitalWrite(LedGopro, LOW); } }

void GoproStartAP() { WiFi.softAPConfig(ip, gateway, subnet); WiFi.softAP(ssid_pilot, "", wifiChannel); Udp.begin(plocalPort); //----------------DEBUG--------------------- // DebugSerial.print("Pilot Mac:"); // DebugSerial.println(WiFi.softAPmacAddress()); // DebugSerial.print("Pilot SSID:"); // DebugSerial.print(ssid_pilot); // DebugSerial.print(" Pilot IP"); // DebugSerial.println(WiFi.softAPIP()); // DebugSerial.println("Pilot w funkcji AP Włączony ON"); }

void GoproStopAP() { Udp.stop(); WiFi.softAPdisconnect(true); //---------------DEBUD----------------------- // DebugSerial.println("Pilot w funkcji AP Wyłączony OFF"); }

void GoproClientStatus() { struct ip4_addr IPaddress; IPAddress address; struct station_info stat_info; stat_info = wifi_softap_get_station_info(); if (stat_info != NULL) { uint8_t* clientBSSID = stat_info->bssid; IPaddress = &stat_info->ip; address = IPaddress->addr; if (address[0] != 0) //(memcmp(clientBSSID, M1BSSID, 6) == 0) { M1IP = address; //---------------DEBUD----------------------- // DebugSerial.println("MacAdres podlaczonego GoPro:" + String(clientBSSID[0], HEX) + ":" + String(clientBSSID[1], HEX) + ":" + String(clientBSSID[2], HEX) + ":" // + String(clientBSSID[3], HEX) + ":" + String(clientBSSID[4], HEX) + ":" + String(clientBSSID[5], HEX)); // DebugSerial.println("IP podlaczonego GoPro:" + String(address[0], DEC) + ":" + String(address[1], DEC) + ":" + String(address[2], DEC) + ":" // + String(address[3], DEC)); } } //---------------DEBUD----------------------- // else {DebugSerial.println("Brak podlaczonych klientow");} wifi_softap_free_station_info(); }

void GoproSendReq(uint8_t req, int noBytes) { struct ip4_addr IPaddress; IPAddress address; stat_info = wifi_softap_get_station_info(); while (stat_info != NULL) { IPaddress = &stat_info->ip; address = IPaddress->addr; M1IP = address; Udp.beginPacket(address, cremotePort); Udp.write(req, noBytes); Udp.endPacket(); stat_info = STAILQ_NEXT(stat_info, next); } wifi_softap_free_station_info(); }

void GoproReciveReq() { int noBytes = Udp.parsePacket();

if (noBytes) { gopro_present=true; Udp.read(packetBuffer, noBytes); // read the packet into the buffer //---------------DEBUD----------------------- // DebugSerial.print(""); // GoproSerialPrintHex(packetBuffer, noBytes); // DebugSerial.println(""); } }

void GoproHeartBeat() { if (rateI >=1 and rateI < 255) {rate2=rateI;rate3=0;} if (rateI >=255 and rateI < 64515) {rate2=rateI/255;rate3=rateI%255;} if (rateI >64515) {rateI=1;rate2=1;rate3=0;} stdMsg[9] = (uint8_t)rate2; stdMsg[10] = (uint8_t)rate3; rateI++; }

void GoproSerialPrintHex(uint8_t msg[], int noBytes) { // String received_command = ""; for (int i = 1; i <= noBytes; i++) { DebugSerial.print(msg[i - 1], HEX); // received_command = received_command + char(msg[i - 1]); if (i % 44 == 0) {DebugSerial.println();} else DebugSerial.print(" "); } }

void GoproReadSession() { stdMsg[11] = se[0]; stdMsg[12] = se[1]; GoproSendReq(stdMsg, 13); delay(200); GoproReciveReq(); GoproHeartBeat(); gopro_rec = 0; gopro_mode = 0;
gopro_time_sec = 0;
gopro_time_min = 0;
if (packetBuffer[24] == 0xFF and packetBuffer[31] == 0x80) { gopro_rec = packetBuffer[43]; gopro_mode = packetBuffer[14];
gopro_time_sec = packetBuffer[27];
gopro_time_min = packetBuffer[26];
if (gopro_rec + gopro_mode + gopro_time_sec + gopro_time_min == 0) {dron_ch8 = 30;} } if (packetBuffer[24] != 0xFF) {gopro_restart = gopro_restart + 1;} if (gopro_restart == 4) {GoproStartCam();} }

void GoproShutterStop() { stdMsg[11] = SH[0]; stdMsg[12] = SH[1]; stdMsg[13] = 0x00; // stop shutter GoproSendReq(stdMsg, 14); delay(500); GoproReciveReq(); GoproHeartBeat(); }

void GoproShutterStart() { stdMsg[11] = SH[0]; stdMsg[12] = SH[1]; stdMsg[13] = 0x01; // start shutter GoproSendReq(stdMsg, 14); delay(500); GoproReciveReq(); GoproHeartBeat(); }

void MavLink_request_datastream() { //Request Data from Pixhawk uint8_t _system_id = 255; // id of computer which is sending the command (ground control software has id of 255) uint8_t _component_id = 25; // ComponentID USER1 //seems like it can be any # except the number of what Pixhawk sys_id is uint8_t _target_system = 1; // Id # of Pixhawk (should be 1) uint8_t _target_component = 1; // Target component, 0 = all (seems to work with 0 or 1) uint8_t _req_stream_id = MAV_DATA_STREAM_RC_CHANNELS; //MAV_DATA_STREAM_ALL; uint16_t _req_message_rate = 0x01; //number of times per second to request the data in hex uint8_t _start_stop = 1; // 1 = start, 0 = stop

// STREAMS that can be requested /*

void MavLink_receive() { mavlink_message_t msg; mavlink_status_t status;

while(MavSerial.available()>0) { uint8_t c= MavSerial.read(); //Get new message if(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) { //--------------DEBUG ------------------- // DebugSerial.print("There is MAVLINK something on DebugSerial MsgID:"); // DebugSerial.println(msg.msgid, DEC); //Handle new message from autopilot millis_mavlink_receive = millis(); //dron_heartbeat = true; switch(msg.msgid) { case MAVLINK_MSG_ID_HEARTBEAT: { if (dron_heartbeat == false) { mavlink_heartbeat_t packet; mavlink_msg_heartbeat_decode(&msg, &packet); if(dron_status != packet.system_status) { //--------------DEBUG ------------------- // if (dron_status != packet.system_status) // { // DebugSerial.print("Custom mode: ");DebugSerial.println(packet.custom_mode); // DebugSerial.print("Type: ");DebugSerial.println(packet.type); // DebugSerial.print("Autopilot: ");DebugSerial.println(packet.autopilot); // DebugSerial.print("Base_mode: ");DebugSerial.println(packet.base_mode); // DebugSerial.print("System Status: ");DebugSerial.println(packet.system_status); // DebugSerial.print("Mavlink version: ");DebugSerial.println(packet.mavlink_version); // } //Custom_mode= ,Type=3 ArdupilotMega,Autopilot= ,Basem_mode= ,System_status= dron_status = packet.system_status; } if (packet.autopilot == 3 and packet.type == 2 and packet.system_status > 0) //jeśli ardupilotmega, quadrocopter i status>0 { dron_heartbeat = true; digitalWrite(LedMavlink, LOW);} //if (millis() - millis_old > 5000) { dron_heartbeat = false; } } } break;

    case MAVLINK_MSG_ID_RC_CHANNELS:
    {
      mavlink_rc_channels_t packet;
      mavlink_msg_rc_channels_decode(&msg, &packet);
      if(dron_ch14 != packet.chan14_raw)
      {

//--------------DEBUG ------------------- // DebugSerial.print("Time: ");DebugSerial.println(packet.time_boot_ms); // DebugSerial.print("Channel 1: ");DebugSerial.println(packet.chan1_raw); // DebugSerial.print("Channel 2: ");DebugSerial.println(packet.chan2_raw); // DebugSerial.print("Channel 3: ");DebugSerial.println(packet.chan3_raw); // DebugSerial.print("Channel 4: ");DebugSerial.println(packet.chan4_raw); // DebugSerial.print("Channel 5: ");DebugSerial.println(packet.chan5_raw); // DebugSerial.print("Channel 6: ");DebugSerial.println(packet.chan6_raw); // DebugSerial.print("Channel 7: ");DebugSerial.println(packet.chan7_raw); // DebugSerial.print("Channel 8: ");DebugSerial.println(packet.chan8_raw); // DebugSerial.print("Channel 9: ");DebugSerial.println(packet.chan9_raw); // DebugSerial.print("Channel 10: ");DebugSerial.println(packet.chan10_raw); // DebugSerial.print("Channel 11: ");DebugSerial.println(packet.chan11_raw); // DebugSerial.print("Channel 12: ");DebugSerial.println(packet.chan12_raw); // DebugSerial.print("Channel 13: ");DebugSerial.println(packet.chan13_raw); // DebugSerial.print("Channel 14: ");DebugSerial.println(packet.chan14_raw); // DebugSerial.print("Channel 15: ");DebugSerial.println(packet.chan15_raw); // DebugSerial.print("Channel 16: ");DebugSerial.println(packet.chan16_raw); // DebugSerial.println(); // DebugSerial.print("Chan count: ");DebugSerial.println(packet.chancount); // DebugSerial.print("RSSI: ");DebugSerial.println(packet.rssi); } dron_ch14 = packet.chan14_raw; //dron_heartbeat = true; } break;

  }
}

} }

void Mavlink_CH8_override(int value) { mavlink_message_t msg; uint8_t buf[MAVLINK_MAX_PACKET_LEN];

mavlink_msg_rc_channels_override_pack(255, 25, &msg, 1, 1, 0, 0, 0, 0, 0, 0, 0, value); uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); MavSerial.write(buf, len);
}

KonradIT commented 4 years ago

Hmm, will look into it as I'm dying out of boredom, trapped in this damn box.

MaxwellNewberry commented 4 years ago

@KonradIT Any update?