mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
AP_ONVIF: add support controlling onvif cam using scripting
This commit is contained in:
parent
cd63dd1720
commit
1db1da9ee5
@ -22,23 +22,6 @@
|
|||||||
// For ChibiOS we will use HW RND # generator
|
// For ChibiOS we will use HW RND # generator
|
||||||
#include <stdlib.h> //rand()
|
#include <stdlib.h> //rand()
|
||||||
|
|
||||||
|
|
||||||
#ifndef USERNAME
|
|
||||||
#define USERNAME "admin"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef PASSWORD
|
|
||||||
#define PASSWORD "admin"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef ONVIF_HOSTNAME
|
|
||||||
#define ONVIF_HOSTNAME "http://10.211.55.3:10000"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define DEVICE_ENDPOINT ONVIF_HOSTNAME"/onvif/device_service"
|
|
||||||
#define MEDIA_ENDPOINT ONVIF_HOSTNAME"/onvif/media_service"
|
|
||||||
#define PTZ_ENDPOINT ONVIF_HOSTNAME"/onvif/ptz_service"
|
|
||||||
|
|
||||||
#ifndef PRINT
|
#ifndef PRINT
|
||||||
#define PRINT(fmt,args...) do {printf(fmt "\n", ## args); } while(0)
|
#define PRINT(fmt,args...) do {printf(fmt "\n", ## args); } while(0)
|
||||||
#endif
|
#endif
|
||||||
@ -46,9 +29,18 @@
|
|||||||
const char *wsse_PasswordDigestURI = "http://docs.oasis-open.org/wss/2004/01/oasis-200401-wss-username-token-profile-1.0#PasswordDigest";
|
const char *wsse_PasswordDigestURI = "http://docs.oasis-open.org/wss/2004/01/oasis-200401-wss-username-token-profile-1.0#PasswordDigest";
|
||||||
const char *wsse_Base64BinaryURI = "http://docs.oasis-open.org/wss/2004/01/oasis-200401-wss-soap-message-security-1.0#Base64Binary";
|
const char *wsse_Base64BinaryURI = "http://docs.oasis-open.org/wss/2004/01/oasis-200401-wss-soap-message-security-1.0#Base64Binary";
|
||||||
|
|
||||||
// static AP _ONVIF *_singleton;
|
AP_ONVIF *AP_ONVIF::_singleton;
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
|
// Default constructor
|
||||||
|
AP_ONVIF::AP_ONVIF()
|
||||||
|
{
|
||||||
|
if (_singleton != nullptr) {
|
||||||
|
AP_HAL::panic("AP_ONVIF must be singleton");
|
||||||
|
}
|
||||||
|
_singleton = this;
|
||||||
|
}
|
||||||
|
|
||||||
bool AP_ONVIF::init()
|
bool AP_ONVIF::init()
|
||||||
{
|
{
|
||||||
srand ((time_t)(hal.util->get_hw_rtc()/1000000ULL));
|
srand ((time_t)(hal.util->get_hw_rtc()/1000000ULL));
|
||||||
@ -65,43 +57,29 @@ bool AP_ONVIF::init()
|
|||||||
AP_HAL::panic("AP_ONVIF: Failed to allocate gSOAP Proxy objects.");
|
AP_HAL::panic("AP_ONVIF: Failed to allocate gSOAP Proxy objects.");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool AP_ONVIF::start(const char *user, const char *pass, const char *httphostname)
|
||||||
|
{
|
||||||
|
username = user;
|
||||||
|
password = pass;
|
||||||
|
hostname = httphostname;
|
||||||
|
|
||||||
|
DEVICE_ENDPOINT = hostname + "/onvif/device_service";
|
||||||
|
MEDIA_ENDPOINT = hostname + "/onvif/media_service";
|
||||||
|
PTZ_ENDPOINT = hostname + "/onvif/ptz_service";
|
||||||
/// 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
|
||||||
proxy_device->soap_endpoint = DEVICE_ENDPOINT;
|
proxy_device->soap_endpoint = DEVICE_ENDPOINT.c_str();
|
||||||
if (!probe_onvif_server()) {
|
if (!probe_onvif_server()) {
|
||||||
PRINT("Failed to probe onvif server.");
|
PRINT("Failed to probe onvif server.");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ONVIF::update, void), "onvif",
|
|
||||||
4096, AP_HAL::Scheduler::PRIORITY_IO, 0)) {
|
|
||||||
PRINT("Failed to create onvif thread");
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_ONVIF::update()
|
|
||||||
{
|
|
||||||
while(true) {
|
|
||||||
float pan = pan_norm;
|
|
||||||
float tilt = tilt_norm;
|
|
||||||
|
|
||||||
// translate them into actual commands using cmd limits
|
|
||||||
pan = ((pan + 1) * (pan_tilt_limit_max.x - pan_tilt_limit_min.x)/2.0) + pan_tilt_limit_min.x;
|
|
||||||
tilt = ((tilt + 1) * (pan_tilt_limit_max.y - pan_tilt_limit_min.y)/2.0) + pan_tilt_limit_min.y;
|
|
||||||
PRINT("PAN: %f TILT: %f", pan, tilt);
|
|
||||||
// don't send the same request again
|
|
||||||
if (uint32_t(pan*100.0) != uint32_t(last_pan_cmd*100.0) || uint32_t(tilt*100.0) != uint32_t(last_tilt_cmd*100.0)) {
|
|
||||||
// actually send the command
|
|
||||||
set_absolutemove(pan, tilt, 0.0);
|
|
||||||
last_pan_cmd = pan;
|
|
||||||
last_tilt_cmd = tilt;
|
|
||||||
}
|
|
||||||
hal.scheduler->delay(100);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void AP_ONVIF::report_error()
|
void AP_ONVIF::report_error()
|
||||||
{
|
{
|
||||||
PRINT("ONVIF ERROR:\n");
|
PRINT("ONVIF ERROR:\n");
|
||||||
@ -171,7 +149,7 @@ bool AP_ONVIF::probe_onvif_server()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// set the Media proxy endpoint to XAddr
|
// set the Media proxy endpoint to XAddr
|
||||||
proxy_media->soap_endpoint = MEDIA_ENDPOINT;
|
proxy_media->soap_endpoint = MEDIA_ENDPOINT.c_str();
|
||||||
|
|
||||||
// get device profiles
|
// get device profiles
|
||||||
_trt__GetProfiles GetProfiles;
|
_trt__GetProfiles GetProfiles;
|
||||||
@ -198,7 +176,7 @@ bool AP_ONVIF::probe_onvif_server()
|
|||||||
// Just use first one for now
|
// Just use first one for now
|
||||||
profile_token = GetProfilesResponse.Profiles[0]->token;
|
profile_token = GetProfilesResponse.Profiles[0]->token;
|
||||||
|
|
||||||
proxy_ptz->soap_endpoint = PTZ_ENDPOINT;
|
proxy_ptz->soap_endpoint = PTZ_ENDPOINT.c_str();
|
||||||
|
|
||||||
// _tptz__GetServiceCapabilities GetCapabilities;
|
// _tptz__GetServiceCapabilities GetCapabilities;
|
||||||
// _tptz__GetServiceCapabilitiesResponse GetCapabilitiesResponse;
|
// _tptz__GetServiceCapabilitiesResponse GetCapabilitiesResponse;
|
||||||
@ -317,7 +295,7 @@ void AP_ONVIF::set_credentials()
|
|||||||
#else
|
#else
|
||||||
sha1_hash((const unsigned char*)nonce, 16, &ctx);
|
sha1_hash((const unsigned char*)nonce, 16, &ctx);
|
||||||
sha1_hash((const unsigned char*)created, strlen(created), &ctx);
|
sha1_hash((const unsigned char*)created, strlen(created), &ctx);
|
||||||
sha1_hash((const unsigned char*)PASSWORD, strlen(PASSWORD), &ctx);
|
sha1_hash((const unsigned char*)password.c_str(), strlen(password.c_str()), &ctx);
|
||||||
nonceBase64 = (char*)base64_encode((unsigned char*)nonce, 16, &noncelen);
|
nonceBase64 = (char*)base64_encode((unsigned char*)nonce, 16, &noncelen);
|
||||||
#endif
|
#endif
|
||||||
sha1_end((unsigned char*)HA, &ctx);
|
sha1_end((unsigned char*)HA, &ctx);
|
||||||
@ -331,7 +309,7 @@ void AP_ONVIF::set_credentials()
|
|||||||
|
|
||||||
memcpy(HABase64fin, HABase64enc, HABase64len);
|
memcpy(HABase64fin, HABase64enc, HABase64len);
|
||||||
|
|
||||||
if (soap_wsse_add_UsernameTokenText(soap, "Auth", USERNAME, HABase64fin)) {
|
if (soap_wsse_add_UsernameTokenText(soap, "Auth", username.c_str(), HABase64fin)) {
|
||||||
report_error();
|
report_error();
|
||||||
}
|
}
|
||||||
/* populate the remainder of the password, nonce, and created */
|
/* populate the remainder of the password, nonce, and created */
|
||||||
|
@ -25,24 +25,33 @@
|
|||||||
|
|
||||||
class AP_ONVIF {
|
class AP_ONVIF {
|
||||||
public:
|
public:
|
||||||
|
AP_ONVIF();
|
||||||
|
|
||||||
|
/* Do not allow copies */
|
||||||
|
AP_ONVIF(const AP_ONVIF &other) = delete;
|
||||||
|
AP_ONVIF &operator=(const AP_ONVIF&) = delete;
|
||||||
|
|
||||||
bool init();
|
bool init();
|
||||||
|
bool start(const char *user, const char *pass, const char *httphostname);
|
||||||
void set_credentials();
|
void set_credentials();
|
||||||
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_pan_norm(float pan) { pan_norm = pan; }
|
||||||
void set_tilt_norm(float tilt) { tilt_norm = tilt; }
|
void set_tilt_norm(float tilt) { tilt_norm = tilt; }
|
||||||
|
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_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:
|
||||||
void report_error();
|
void report_error();
|
||||||
bool probe_onvif_server();
|
bool probe_onvif_server();
|
||||||
void rand_nonce(char *nonce, size_t noncelen);
|
void rand_nonce(char *nonce, size_t noncelen);
|
||||||
void update();
|
|
||||||
|
|
||||||
Vector2f pan_tilt_limit_min;
|
Vector2f pan_tilt_limit_min;
|
||||||
Vector2f pan_tilt_limit_max;
|
Vector2f pan_tilt_limit_max;
|
||||||
float pan_norm, tilt_norm;
|
float pan_norm, tilt_norm, zoom_norm;
|
||||||
float last_pan_cmd, last_tilt_cmd;
|
float last_pan_cmd, last_tilt_cmd;
|
||||||
|
|
||||||
float zoom_min, zoom_max;
|
float zoom_min, zoom_max;
|
||||||
@ -53,9 +62,17 @@ private:
|
|||||||
PTZBindingProxy *proxy_ptz;
|
PTZBindingProxy *proxy_ptz;
|
||||||
static AP_ONVIF *_singleton;
|
static AP_ONVIF *_singleton;
|
||||||
char* media_endpoint;
|
char* media_endpoint;
|
||||||
|
|
||||||
|
std::string username;
|
||||||
|
std::string password;
|
||||||
|
std::string hostname;
|
||||||
|
|
||||||
|
std::string DEVICE_ENDPOINT;
|
||||||
|
std::string MEDIA_ENDPOINT;
|
||||||
|
std::string PTZ_ENDPOINT;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
// namespace AP {
|
namespace AP {
|
||||||
// AP_ONVIF *onvif();
|
AP_ONVIF &onvif();
|
||||||
// };
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user