mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ONVIF: remove init method and move initialisation to start
This commit is contained in:
parent
d3fce3c41d
commit
5f82ef83ad
@ -16,6 +16,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_ONVIF.h"
|
#include "AP_ONVIF.h"
|
||||||
|
#if ENABLE_ONVIF
|
||||||
#include <AP_ONVIF/MediaBinding.nsmap>
|
#include <AP_ONVIF/MediaBinding.nsmap>
|
||||||
|
|
||||||
#include "onvifhelpers.h"
|
#include "onvifhelpers.h"
|
||||||
@ -31,6 +32,7 @@ const char *wsse_Base64BinaryURI = "http://docs.oasis-open.org/wss/2004/01/oasis
|
|||||||
|
|
||||||
AP_ONVIF *AP_ONVIF::_singleton;
|
AP_ONVIF *AP_ONVIF::_singleton;
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
static AP_ONVIF onvif;
|
||||||
|
|
||||||
// Default constructor
|
// Default constructor
|
||||||
AP_ONVIF::AP_ONVIF()
|
AP_ONVIF::AP_ONVIF()
|
||||||
@ -41,27 +43,26 @@ AP_ONVIF::AP_ONVIF()
|
|||||||
_singleton = this;
|
_singleton = this;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_ONVIF::init()
|
// Start ONVIF client with username, password and service host url
|
||||||
{
|
|
||||||
srand ((time_t)(hal.util->get_hw_rtc()/1000000ULL));
|
|
||||||
soap = soap_new1(SOAP_XML_CANONICAL | SOAP_C_UTFSTRING);
|
|
||||||
soap->connect_timeout = soap->recv_timeout = soap->send_timeout = 30; // 30 sec
|
|
||||||
|
|
||||||
proxy_device = new DeviceBindingProxy(soap);
|
|
||||||
proxy_media = new MediaBindingProxy(soap);
|
|
||||||
proxy_ptz = new PTZBindingProxy(soap);
|
|
||||||
|
|
||||||
if (proxy_device == nullptr ||
|
|
||||||
proxy_media == nullptr ||
|
|
||||||
proxy_ptz == nullptr) {
|
|
||||||
AP_HAL::panic("AP_ONVIF: Failed to allocate gSOAP Proxy objects.");
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
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 *httphostname)
|
||||||
{
|
{
|
||||||
|
if (!initialised) {
|
||||||
|
srand ((time_t)(hal.util->get_hw_rtc()/1000000ULL));
|
||||||
|
soap = soap_new1(SOAP_XML_CANONICAL | SOAP_C_UTFSTRING);
|
||||||
|
soap->connect_timeout = soap->recv_timeout = soap->send_timeout = 30; // 30 sec
|
||||||
|
|
||||||
|
proxy_device = new DeviceBindingProxy(soap);
|
||||||
|
proxy_media = new MediaBindingProxy(soap);
|
||||||
|
proxy_ptz = new PTZBindingProxy(soap);
|
||||||
|
|
||||||
|
if (proxy_device == nullptr ||
|
||||||
|
proxy_media == nullptr ||
|
||||||
|
proxy_ptz == nullptr) {
|
||||||
|
AP_HAL::panic("AP_ONVIF: Failed to allocate gSOAP Proxy objects.");
|
||||||
|
}
|
||||||
|
initialised = true;
|
||||||
|
}
|
||||||
|
|
||||||
username = user;
|
username = user;
|
||||||
password = pass;
|
password = pass;
|
||||||
hostname = httphostname;
|
hostname = httphostname;
|
||||||
@ -104,6 +105,7 @@ void AP_ONVIF::report_error()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// detect onvif server present on the network
|
||||||
bool AP_ONVIF::probe_onvif_server()
|
bool AP_ONVIF::probe_onvif_server()
|
||||||
{
|
{
|
||||||
_tds__GetDeviceInformation GetDeviceInformation;
|
_tds__GetDeviceInformation GetDeviceInformation;
|
||||||
@ -250,6 +252,7 @@ bool AP_ONVIF::probe_onvif_server()
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Generate Random Nonce value
|
||||||
void AP_ONVIF::rand_nonce(char *nonce, size_t noncelen)
|
void AP_ONVIF::rand_nonce(char *nonce, size_t noncelen)
|
||||||
{
|
{
|
||||||
size_t i;
|
size_t i;
|
||||||
@ -261,6 +264,7 @@ void AP_ONVIF::rand_nonce(char *nonce, size_t noncelen)
|
|||||||
(void)memcpy((void *)(nonce + i), (const void *)&r, 4);
|
(void)memcpy((void *)(nonce + i), (const void *)&r, 4);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#define TEST_NONCE "LKqI6G/AikKCQrN0zqZFlg=="
|
#define TEST_NONCE "LKqI6G/AikKCQrN0zqZFlg=="
|
||||||
#define TEST_TIME "2010-09-16T07:50:45Z"
|
#define TEST_TIME "2010-09-16T07:50:45Z"
|
||||||
#define TEST_PASS "userpassword"
|
#define TEST_PASS "userpassword"
|
||||||
@ -326,6 +330,8 @@ void AP_ONVIF::set_credentials()
|
|||||||
security->UsernameToken->wsu__Created = soap_strdup(soap, created);
|
security->UsernameToken->wsu__Created = soap_strdup(soap, created);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Turn ONVIF camera to mentioned pan, tilt and zoom, normalised
|
||||||
|
// between limits
|
||||||
bool AP_ONVIF::set_absolutemove(float x, float y, float z)
|
bool AP_ONVIF::set_absolutemove(float x, float y, float z)
|
||||||
{
|
{
|
||||||
_tptz__AbsoluteMove AbsoluteMove;
|
_tptz__AbsoluteMove AbsoluteMove;
|
||||||
@ -353,3 +359,4 @@ bool AP_ONVIF::set_absolutemove(float x, float y, float z)
|
|||||||
soap_end(soap);
|
soap_end(soap);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
#endif //#if ENABLE_ONVIF
|
||||||
|
@ -17,6 +17,8 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
#if ENABLE_ONVIF
|
||||||
#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>
|
||||||
@ -31,22 +33,34 @@ public:
|
|||||||
AP_ONVIF(const AP_ONVIF &other) = delete;
|
AP_ONVIF(const AP_ONVIF &other) = delete;
|
||||||
AP_ONVIF &operator=(const AP_ONVIF&) = delete;
|
AP_ONVIF &operator=(const AP_ONVIF&) = delete;
|
||||||
|
|
||||||
bool init();
|
// Start ONVIF client with username, password and service host url
|
||||||
bool start(const char *user, const char *pass, const char *httphostname);
|
bool start(const char *user, const char *pass, const char *httphostname);
|
||||||
void set_credentials();
|
|
||||||
|
// Turn ONVIF camera to mentioned pan, tilt and zoom, normalised
|
||||||
|
// between limits
|
||||||
bool set_absolutemove(float pan, float tilt, float zoom);
|
bool set_absolutemove(float pan, float tilt, float zoom);
|
||||||
void set_pan_norm(float pan) { pan_norm = pan; }
|
|
||||||
void set_tilt_norm(float tilt) { tilt_norm = tilt; }
|
// returns pan/tilt command max limit
|
||||||
void set_zoom_norm(float zoom) { zoom_norm = zoom; }
|
|
||||||
Vector2f get_pan_tilt_limit_max() const { return pan_tilt_limit_max; }
|
Vector2f get_pan_tilt_limit_max() const { return pan_tilt_limit_max; }
|
||||||
|
|
||||||
|
// returns pan/tilt command min limit
|
||||||
Vector2f get_pan_tilt_limit_min() const { return pan_tilt_limit_min; }
|
Vector2f get_pan_tilt_limit_min() const { return pan_tilt_limit_min; }
|
||||||
|
|
||||||
// get singleton instance
|
// get singleton instance
|
||||||
static AP_ONVIF *get_singleton() { return _singleton; }
|
static AP_ONVIF *get_singleton() { return _singleton; }
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
// prepares security header of SOAP message going to be sent immmediately after
|
||||||
|
void set_credentials();
|
||||||
|
|
||||||
|
// convert error message from gSOAP lib into human readable string and print
|
||||||
void report_error();
|
void report_error();
|
||||||
|
|
||||||
|
// detect onvif server present on the network
|
||||||
bool probe_onvif_server();
|
bool probe_onvif_server();
|
||||||
|
|
||||||
|
// Generate Random Nonce value
|
||||||
void rand_nonce(char *nonce, size_t noncelen);
|
void rand_nonce(char *nonce, size_t noncelen);
|
||||||
|
|
||||||
Vector2f pan_tilt_limit_min;
|
Vector2f pan_tilt_limit_min;
|
||||||
@ -70,9 +84,11 @@ private:
|
|||||||
std::string DEVICE_ENDPOINT;
|
std::string DEVICE_ENDPOINT;
|
||||||
std::string MEDIA_ENDPOINT;
|
std::string MEDIA_ENDPOINT;
|
||||||
std::string PTZ_ENDPOINT;
|
std::string PTZ_ENDPOINT;
|
||||||
|
bool initialised;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
AP_ONVIF &onvif();
|
AP_ONVIF &onvif();
|
||||||
};
|
};
|
||||||
|
#endif // #if ENABLE_ONVIF
|
||||||
|
@ -37,6 +37,7 @@
|
|||||||
|
|
||||||
#include "onvifhelpers.h"
|
#include "onvifhelpers.h"
|
||||||
|
|
||||||
|
#ifdef __BYTE_ORDER
|
||||||
#define SHA1_BLOCK_SIZE 64
|
#define SHA1_BLOCK_SIZE 64
|
||||||
|
|
||||||
#define rotl32(x,n) (((x) << n) | ((x) >> (32 - n)))
|
#define rotl32(x,n) (((x) << n) | ((x) >> (32 - n)))
|
||||||
@ -231,3 +232,4 @@ void sha1(unsigned char hval[], const unsigned char data[], unsigned long len)
|
|||||||
|
|
||||||
sha1_begin(cx); sha1_hash(data, len, cx); sha1_end(hval, cx);
|
sha1_begin(cx); sha1_hash(data, len, cx); sha1_end(hval, cx);
|
||||||
}
|
}
|
||||||
|
#endif //#ifdef __BYTE_ORDER
|
||||||
|
Loading…
Reference in New Issue
Block a user