mirror of https://github.com/ArduPilot/ardupilot
AP_ONVIF: make onvif test empty if ONVIF not enabled
This commit is contained in:
parent
51a6d3c16a
commit
2f8dec7c9b
|
@ -52,10 +52,9 @@ AP_ONVIF::AP_ONVIF()
|
||||||
}
|
}
|
||||||
|
|
||||||
// Start ONVIF client with username, password and service host url
|
// Start ONVIF client with username, password and service host url
|
||||||
bool AP_ONVIF::start(const char *user, const char *pass, const char *httphostname)
|
bool AP_ONVIF::start(const char *user, const char *pass, const char *hostname)
|
||||||
{
|
{
|
||||||
if (!initialised) {
|
if (!initialised) {
|
||||||
srand ((time_t)(hal.util->get_hw_rtc()/1000000ULL));
|
|
||||||
soap = soap_new1(SOAP_XML_CANONICAL | SOAP_C_UTFSTRING);
|
soap = soap_new1(SOAP_XML_CANONICAL | SOAP_C_UTFSTRING);
|
||||||
if (soap == nullptr) {
|
if (soap == nullptr) {
|
||||||
ERROR_PRINT("AP_ONVIF: Failed to allocate soap");
|
ERROR_PRINT("AP_ONVIF: Failed to allocate soap");
|
||||||
|
@ -82,30 +81,70 @@ bool AP_ONVIF::start(const char *user, const char *pass, const char *httphostnam
|
||||||
initialised = true;
|
initialised = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
username = user;
|
if (strlen(user) > username_len) {
|
||||||
password = pass;
|
if (username != nullptr) {
|
||||||
hostname = httphostname;
|
free(username);
|
||||||
|
username = nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
username_len = strlen(user);
|
||||||
|
if (username == nullptr) {
|
||||||
|
username = (char*)malloc(username_len + 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (strlen(pass) > password_len) {
|
||||||
|
if (password != nullptr) {
|
||||||
|
free(password);
|
||||||
|
password = nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
password_len = strlen(pass);
|
||||||
|
if (password == nullptr) {
|
||||||
|
password = (char*)malloc(password_len+1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (strlen(hostname) > hostname_len) {
|
||||||
|
// free if not nullptr
|
||||||
|
if (device_endpoint != nullptr) {
|
||||||
|
free(device_endpoint);
|
||||||
|
device_endpoint = nullptr;
|
||||||
|
}
|
||||||
|
if (media_endpoint != nullptr) {
|
||||||
|
free(media_endpoint);
|
||||||
|
media_endpoint = nullptr;
|
||||||
|
}
|
||||||
|
if (ptz_endpoint != nullptr) {
|
||||||
|
free(ptz_endpoint);
|
||||||
|
ptz_endpoint = nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
hostname_len = strlen(hostname);
|
||||||
|
|
||||||
if (device_endpoint == nullptr) {
|
if (device_endpoint == nullptr) {
|
||||||
device_endpoint = (char*)malloc(strlen(hostname) + strlen(DEVICE_ENDPOINT_LOC) + 1);
|
device_endpoint = (char*)malloc(hostname_len + strlen(DEVICE_ENDPOINT_LOC) + 1);
|
||||||
}
|
}
|
||||||
if (media_endpoint == nullptr) {
|
if (media_endpoint == nullptr) {
|
||||||
media_endpoint = (char*)malloc(strlen(hostname) + strlen(MEDIA_ENDPOINT_LOC) + 1);
|
media_endpoint = (char*)malloc(hostname_len + strlen(MEDIA_ENDPOINT_LOC) + 1);
|
||||||
}
|
}
|
||||||
if (ptz_endpoint == nullptr) {
|
if (ptz_endpoint == nullptr) {
|
||||||
ptz_endpoint = (char*)malloc(strlen(hostname) + strlen(PTZ_ENDPOINT_LOC) + 1);
|
ptz_endpoint = (char*)malloc(hostname_len + strlen(PTZ_ENDPOINT_LOC) + 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (device_endpoint == nullptr ||
|
if (device_endpoint == nullptr ||
|
||||||
media_endpoint == nullptr ||
|
media_endpoint == nullptr ||
|
||||||
ptz_endpoint == nullptr) {
|
ptz_endpoint == nullptr ||
|
||||||
ERROR_PRINT("Failed to Allocate endpoint strings");
|
username == nullptr ||
|
||||||
|
password == nullptr) {
|
||||||
|
ERROR_PRINT("Failed to Allocate strings");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
snprintf(device_endpoint, strlen(hostname) + strlen(DEVICE_ENDPOINT_LOC) + 1, "%s" DEVICE_ENDPOINT_LOC, hostname);
|
strcpy(username, user);
|
||||||
snprintf(media_endpoint, strlen(hostname) + strlen(MEDIA_ENDPOINT_LOC) + 1, "%s" MEDIA_ENDPOINT_LOC, hostname);
|
strcpy(password, pass);
|
||||||
snprintf(ptz_endpoint, strlen(hostname) + strlen(PTZ_ENDPOINT_LOC) + 1, "%s" PTZ_ENDPOINT_LOC, hostname);
|
snprintf(device_endpoint, hostname_len + strlen(DEVICE_ENDPOINT_LOC) + 1, "%s" DEVICE_ENDPOINT_LOC, hostname);
|
||||||
|
snprintf(media_endpoint, hostname_len + strlen(MEDIA_ENDPOINT_LOC) + 1, "%s" MEDIA_ENDPOINT_LOC, hostname);
|
||||||
|
snprintf(ptz_endpoint, hostname_len + strlen(PTZ_ENDPOINT_LOC) + 1, "%s" PTZ_ENDPOINT_LOC, hostname);
|
||||||
|
|
||||||
/// TODO: Need to find a way to store this in parameter system
|
/// TODO: Need to find a way to store this in parameter system
|
||||||
// or it could be just storage, we will see
|
// or it could be just storage, we will see
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#if ENABLE_ONVIF
|
#if ENABLE_ONVIF
|
||||||
#pragma GCC diagnostic push
|
#pragma GCC diagnostic push
|
||||||
#pragma GCC diagnostic ignored "-Wshadow"
|
#pragma GCC diagnostic ignored "-Wshadow"
|
||||||
|
#pragma GCC diagnostic ignored "-Wsuggest-override"
|
||||||
#include <AP_ONVIF/onvifDeviceBindingProxy.h>
|
#include <AP_ONVIF/onvifDeviceBindingProxy.h>
|
||||||
#include <AP_ONVIF/onvifMediaBindingProxy.h>
|
#include <AP_ONVIF/onvifMediaBindingProxy.h>
|
||||||
#include <AP_ONVIF/onvifPTZBindingProxy.h>
|
#include <AP_ONVIF/onvifPTZBindingProxy.h>
|
||||||
|
@ -80,9 +81,13 @@ private:
|
||||||
PTZBindingProxy *proxy_ptz;
|
PTZBindingProxy *proxy_ptz;
|
||||||
static AP_ONVIF *_singleton;
|
static AP_ONVIF *_singleton;
|
||||||
|
|
||||||
const char* username;
|
char* username;
|
||||||
const char* password;
|
size_t username_len;
|
||||||
const char* hostname;
|
|
||||||
|
char* password;
|
||||||
|
size_t password_len;
|
||||||
|
|
||||||
|
size_t hostname_len;
|
||||||
|
|
||||||
char* device_endpoint;
|
char* device_endpoint;
|
||||||
char* media_endpoint;
|
char* media_endpoint;
|
||||||
|
|
|
@ -40,7 +40,7 @@ static const uint8_t base64url_table[65] = "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghij
|
||||||
* nul terminated to make it easier to use as a C string. The nul terminator is
|
* nul terminated to make it easier to use as a C string. The nul terminator is
|
||||||
* not included in out_len.
|
* not included in out_len.
|
||||||
*/
|
*/
|
||||||
uint8_t* base64_encode_global(const uint8_t *src, uint16_t len, uint16_t *out_len, const uint8_t* table, bool urlsafe)
|
static uint8_t* base64_encode_global(const uint8_t *src, uint16_t len, uint16_t *out_len, const uint8_t* table, bool urlsafe)
|
||||||
{
|
{
|
||||||
uint8_t *out, *pos;
|
uint8_t *out, *pos;
|
||||||
const uint8_t *end, *in;
|
const uint8_t *end, *in;
|
||||||
|
|
|
@ -7,9 +7,10 @@
|
||||||
|
|
||||||
void setup();
|
void setup();
|
||||||
void loop();
|
void loop();
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
|
#if ENABLE_ONVIF
|
||||||
|
|
||||||
AP_ONVIF onvif;
|
AP_ONVIF onvif;
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
|
@ -41,5 +42,8 @@ void loop()
|
||||||
}
|
}
|
||||||
hal.scheduler->delay(10000);
|
hal.scheduler->delay(10000);
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
void setup() {}
|
||||||
|
void loop() {}
|
||||||
|
#endif
|
||||||
AP_HAL_MAIN();
|
AP_HAL_MAIN();
|
||||||
|
|
|
@ -60,6 +60,7 @@ void sha1_end(unsigned char hval[], sha1_ctx ctx[1]);
|
||||||
void sha1(unsigned char hval[], const unsigned char data[], unsigned long len);
|
void sha1(unsigned char hval[], const unsigned char data[], unsigned long len);
|
||||||
uint8_t* base64_encode(const uint8_t *src, uint16_t len, uint16_t *out_len);
|
uint8_t* base64_encode(const uint8_t *src, uint16_t len, uint16_t *out_len);
|
||||||
uint8_t* base64_decode(const uint8_t *src, uint16_t len, uint16_t *out_len);
|
uint8_t* base64_decode(const uint8_t *src, uint16_t len, uint16_t *out_len);
|
||||||
|
uint8_t* base64url_encode(const uint8_t *src, uint16_t len, uint16_t *out_len);
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue