需求
需要在無人艇上添加海康威視的實時攝像頭。
- 本地IP192.168.0.100 攝像頭IP 192.168.0.64 用戶名admin 密碼nanfoon51077533 端口8000
- 海康配置可在文件中更改。
- 攝像頭添加在BoatStatus頁的右側地圖模塊的右上角。
- 通過一個按鈕來控制攝像頭的開啓和關閉。
- 圖像雙擊後彈出獨立窗口。
攝像頭未開啓時的效果圖:
攝像頭開啓後的效果圖:
彈出後的獨立窗口示意圖:
實現
1. 添加按鈕
地圖頁在MissionPlanner項目下面的GCSViews文件夾裏面的FlightData.cs裏面。如下圖:
從toolbox裏面找到Button,拖至地圖位置,並將其text屬性更改。如圖所示:
2. 更改海康威視參數
因爲公司海康威視通用同一個配置參數,先要更改設備參數。進入海康威視的配置軟件:
點擊添加至客戶端後會彈出下面的窗口,輸入原參數,起一個別名,點擊添加。
選中剛纔添加的設備,點擊遠程配置
生效後不要忘記更改本地計算機的IP地址。再次進入遠程配置,更改密碼
順帶把OSD顯示改下:
3. 添加視頻窗口
在toolbox裏面找到pictureBox拖入地圖右上側。並將其visible屬性改爲false,size改爲300,300.
4. 添加視頻代碼
雙擊Camera按鍵進入點擊事件代碼塊。
設備網絡SDK開發包(64bit)【庫文件】裏的HCNetSDK.dll、HCCore.dll、HCNetSDKCom文件夾、PlayCtrl.dll、SuperRender.dll、AudioRender.dll、ssleay32.dll、libeay32.dll等文件均拷貝放置在新建的bin文件夾裏,將bin文件夾放置在Debug目錄下。本例中 C:\Users\lenovo\Documents\Visual Studio 2017\Projects\FlotillaV4\FlotillaV4\bin\Debug
將海康實時預覽示例代碼一\PreviewDemo文件夾裏的CHCNetSDK.cs複製到FlightData.cs相同文件夾下。右擊將其添加如當前project。
雙擊打開,將第三行的namespace更改,如下:
namespace PreviewDemo
改爲
namespace MissionPlanner.GCSViews
更改後導入進去的CHCNetSDK.cs文件可被FlightData.cs識別。
在新增的按鍵點擊事件代碼塊添加以下代碼:
//HikVision Camera
private bool m_bInitSDK = false;
private void ButtonCameraSwitch_Click(object sender, EventArgs e)
{
m_bInitSDK = CHCNetSDK.NET_DVR_Init();
if (m_bInitSDK == false)
{
MessageBox.Show("NET_DVR_Init error!");
return;
}
else
{
//保存SDK日誌 To save the SDK log
CHCNetSDK.NET_DVR_SetLogToFile(3, "C:\\SdkLog\\", true);
}
}
添加完成後點擊調試,啓動調式運行,程序啓動後點擊按鍵,如無報錯,說明添加進去的模塊運行正常。繼續編寫。
在按鍵單擊函數下方添加海康威視的資源釋放函數,如下所示(添加後會提示重名或者變量未定義的錯誤,根據提示修改下就可以):
//HikVision Camera
private bool m_bInitSDK = false;
private Int32 m_lRealHandle = -1;
private Int32 m_lUserID = -1;
private void ButtonCameraSwitch_Click(object sender, EventArgs e)
{
m_bInitSDK = CHCNetSDK.NET_DVR_Init();
if (m_bInitSDK == false)
{
MessageBox.Show("NET_DVR_Init error!");
return;
}
else
{
//保存SDK日誌 To save the SDK log
CHCNetSDK.NET_DVR_SetLogToFile(3, "C:\\SdkLog\\", true);
}
}
/// <summary>
/// 清理所有正在使用的資源。
/// </summary>
protected void HikDispose(bool disposing)
{
if (m_lRealHandle >= 0)
{
CHCNetSDK.NET_DVR_StopRealPlay(m_lRealHandle);
}
if (m_lUserID >= 0)
{
CHCNetSDK.NET_DVR_Logout(m_lUserID);
}
if (m_bInitSDK == true)
{
CHCNetSDK.NET_DVR_Cleanup();
}
if (disposing)
{
if (components != null)
{
components.Dispose();
}
}
base.Dispose(disposing);
}
相同的方法添加更改所需代碼,爲了靈活變換顯示區域,對preview代碼塊做了傳遞函數的更改,將picturebox作爲傳遞變量改進去。代碼塊更改完後如下:
//HikVision Camera
private bool m_bInitSDK = false;
private Int32 m_lRealHandle = -1;
private Int32 m_lUserID = -1;
private uint iLastErr = 0;
private string str;
CHCNetSDK.REALDATACALLBACK RealData = null;
private void ButtonCameraSwitch_Click(object sender, EventArgs e)
{
m_bInitSDK = CHCNetSDK.NET_DVR_Init();
if (m_bInitSDK == false)
{
MessageBox.Show("NET_DVR_Init error!");
return;
}
else
{
//保存SDK日誌 To save the SDK log
CHCNetSDK.NET_DVR_SetLogToFile(3, "C:\\SdkLog\\", true);
}
if (m_lUserID < 0)
{//Open
HikLogin();
HikPreview(PictureBoxHikVisionCameraOnMap);
}
else
{//Close
HikPreview(PictureBoxHikVisionCameraOnMap);
HikLogin();
}
}
/// <summary>
/// 清理所有正在使用的資源。
/// </summary>
protected void HikDispose(bool disposing)
{
if (m_lRealHandle >= 0)
{
CHCNetSDK.NET_DVR_StopRealPlay(m_lRealHandle);
}
if (m_lUserID >= 0)
{
CHCNetSDK.NET_DVR_Logout(m_lUserID);
}
if (m_bInitSDK == true)
{
CHCNetSDK.NET_DVR_Cleanup();
}
if (disposing)
{
if (components != null)
{
components.Dispose();
}
}
base.Dispose(disposing);
}
/// <summary>
/// Login
/// </summary>
protected void HikLogin()
{
if (m_lUserID < 0)
{
string DVRIPAddress = ConfigurationManager.AppSettings["HikIP"]; //設備IP地址或者域名
Int16 DVRPortNumber = Convert.ToInt16(ConfigurationManager.AppSettings["HikPort"]);//設備服務端口號
string DVRUserName = ConfigurationManager.AppSettings["UserName"];//設備登錄用戶名
string DVRPassword = ConfigurationManager.AppSettings["PassWord"];//設備登錄密碼
CHCNetSDK.NET_DVR_DEVICEINFO_V30 DeviceInfo = new CHCNetSDK.NET_DVR_DEVICEINFO_V30();
//登錄設備 Login the device
m_lUserID = CHCNetSDK.NET_DVR_Login_V30(DVRIPAddress, DVRPortNumber, DVRUserName, DVRPassword, ref DeviceInfo);
if (m_lUserID < 0)
{
iLastErr = CHCNetSDK.NET_DVR_GetLastError();
str = "NET_DVR_Login_V30 failed, error code= " + iLastErr; //登錄失敗,輸出錯誤號
MessageBox.Show(str);
return;
}
else
{
//登錄成功
// MessageBox.Show("Login Success!");
// CustomMessageBox.Show("Login Success!");
// btnLogin.Text = "Logout";
}
}
else
{
//註銷登錄 Logout the device
if (m_lRealHandle >= 0)
{
MessageBox.Show("Please stop live view firstly");
return;
}
if (!CHCNetSDK.NET_DVR_Logout(m_lUserID))
{
iLastErr = CHCNetSDK.NET_DVR_GetLastError();
str = "NET_DVR_Logout failed, error code= " + iLastErr;
MessageBox.Show(str);
return;
}
m_lUserID = -1;
// btnLogin.Text = "Login";
}
return;
}
/// <summary>
/// HikPreview
/// </summary>
private void HikPreview( PictureBox pictrueBox )
{
if (m_lUserID < 0)
{
MessageBox.Show("Please login the device firstly");
return;
}
if (m_lRealHandle < 0)
{
CHCNetSDK.NET_DVR_PREVIEWINFO lpPreviewInfo = new CHCNetSDK.NET_DVR_PREVIEWINFO();
lpPreviewInfo.hPlayWnd = pictrueBox.Handle;//預覽窗口
lpPreviewInfo.lChannel = 1;//預te覽的設備通道
lpPreviewInfo.dwStreamType = 0;//碼流類型:0-主碼流,1-子碼流,2-碼流3,3-碼流4,以此類推
lpPreviewInfo.dwLinkMode = 0;//連接方式:0- TCP方式,1- UDP方式,2- 多播方式,3- RTP方式,4-RTP/RTSP,5-RSTP/HTTP
lpPreviewInfo.bBlocked = true; //0- 非阻塞取流,1- 阻塞取流
lpPreviewInfo.dwDisplayBufNum = 1; //播放庫播放緩衝區最大緩衝幀數
lpPreviewInfo.byProtoType = 0;
lpPreviewInfo.byPreviewMode = 0;
//if (textBoxID.Text != "")
//{
// lpPreviewInfo.lChannel = -1;
// byte[] byStreamID = System.Text.Encoding.Default.GetBytes(textBoxID.Text);
// lpPreviewInfo.byStreamID = new byte[32];
// byStreamID.CopyTo(lpPreviewInfo.byStreamID, 0);
//}
if (RealData == null)
{
RealData = new CHCNetSDK.REALDATACALLBACK(HikRealDataCallBack);//預覽實時流回調函數
}
IntPtr pUser = new IntPtr();//用戶數據
//打開預覽 Start live view
m_lRealHandle = CHCNetSDK.NET_DVR_RealPlay_V40(m_lUserID, ref lpPreviewInfo, null/*RealData*/, pUser);
if (m_lRealHandle < 0)
{
iLastErr = CHCNetSDK.NET_DVR_GetLastError();
str = "NET_DVR_RealPlay_V40 failed, error code= " + iLastErr; //預覽失敗,輸出錯誤號
MessageBox.Show(str);
return;
}
else
{
//預覽成功
ButtonCameraSwitch.Text = "Stop";
pictrueBox.Visible = true;
}
}
else
{
//停止預覽 Stop live view
if (!CHCNetSDK.NET_DVR_StopRealPlay(m_lRealHandle))
{
iLastErr = CHCNetSDK.NET_DVR_GetLastError();
str = "NET_DVR_StopRealPlay failed, error code= " + iLastErr;
MessageBox.Show(str);
return;
}
m_lRealHandle = -1;
ButtonCameraSwitch.Text = "Camera";
pictrueBox.Visible = false;
}
return;
}
/// <summary>
/// HikCallBack
/// </summary>
public void HikRealDataCallBack(Int32 lRealHandle, UInt32 dwDataType, IntPtr pBuffer, UInt32 dwBufSize, IntPtr pUser)
{
if (dwBufSize > 0)
{
byte[] sData = new byte[dwBufSize];
System.Runtime.InteropServices.Marshal.Copy(pBuffer, sData, 0, (Int32)dwBufSize);
string str = "實時流數據.ps";
FileStream fs = new FileStream(str, FileMode.Create);
int iLen = (int)dwBufSize;
fs.Write(sData, 0, iLen);
fs.Close();
}
}
5. 海康配置改爲可在文件中更改
在FlightData.cs添加 using System.Configuration; 引用。然後在啓動文件夾下找到exe.config後綴的文件,打開,找到<appSettings>字段,如下所示:
<appSettings>
<add key="UpdateLocationVersion" value="http://firmware.ardupilot.org/MissionPlanner/upgrade/version.txt" />
<add key="UpdateLocation" value="http://firmware.ardupilot.org/MissionPlanner/upgrade/" />
<add key="UpdateLocationMD5" value="http://firmware.ardupilot.org/MissionPlanner/checksums.txt" />
<add key="UpdateLocationZip" value="http://firmware.ardupilot.org/MissionPlanner/MissionPlanner-latest.zip" />
<add key="BetaUpdateLocationVersion" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/version.txt?tag=beta" />
<add key="BetaUpdateLocationMD5" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/checksums.txt?tag=beta" />
<add key="BetaUpdateLocationZip" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/MissionPlannerBeta.zip?tag=beta" />
<add key="MasterUpdateLocationMD5" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/checksums.txt?branch=master" />
<add key="MasterUpdateLocationZip" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/MissionPlannerBeta.zip?branch=master" />
<add key="ParameterLocations" value="https://raw.githubusercontent.com/ardupilot/ardupilot/ArduCopter-stable/ArduCopter/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/ArduSub-stable/ArduSub/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/ArduPlane-stable/ArduPlane/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/APMrover2-stable/APMrover2/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/AntennaTracker/Parameters.cpp;" />
<add key="ParameterLocationsBleeding" value="https://raw.githubusercontent.com/ardupilot/ardupilot/master/ArduCopter/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/ArduSub/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/ArduPlane/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/APMrover2/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/AntennaTracker/Parameters.cpp;" />
<add key="ParameterMetaDataXMLFileName" value="ParameterMetaData.xml" />
<add key="ParameterMetaDataXMLFileNameBackup" value="ParameterMetaDataBackup.xml" />
<add key="ClientId" value="zHTnuEq0RAWoLy5thcvTtMdwX7r6et2L3MAhxv8a0" />
<add key="ClientSecret" value="1ylYlXV4GuWJHIUywFg+XxE6hxsd3P/Dq5+J1PCUGxulC05/GC4Xpg==" />
<add key="AuthURL" value="https://auth.altitudeangel.com" />
<add key="APIURL" value="https://api.altitudeangel.com" />
<add key="ClientSettingsProvider.ServiceUri" value="" />
</appSettings>
在開始位置添加海康配置字段,如下:
<appSettings>
<add key="LocalIP" value="192.168.0.100"/>
<add key="HikIP" value="192.168.0.64"/>
<add key="UserName" value="admin"/>
<add key="PassWord" value="nanfoon51077533"/>
<add key="HikPort" value="8000"/>
<add key="UpdateLocationVersion" value="http://firmware.ardupilot.org/MissionPlanner/upgrade/version.txt" />
<add key="UpdateLocation" value="http://firmware.ardupilot.org/MissionPlanner/upgrade/" />
<add key="UpdateLocationMD5" value="http://firmware.ardupilot.org/MissionPlanner/checksums.txt" />
<add key="UpdateLocationZip" value="http://firmware.ardupilot.org/MissionPlanner/MissionPlanner-latest.zip" />
<add key="BetaUpdateLocationVersion" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/version.txt?tag=beta" />
<add key="BetaUpdateLocationMD5" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/checksums.txt?tag=beta" />
<add key="BetaUpdateLocationZip" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/MissionPlannerBeta.zip?tag=beta" />
<add key="MasterUpdateLocationMD5" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/checksums.txt?branch=master" />
<add key="MasterUpdateLocationZip" value="https://ci.appveyor.com/api/projects/meee1/missionplanner/artifacts/MissionPlannerBeta.zip?branch=master" />
<add key="ParameterLocations" value="https://raw.githubusercontent.com/ardupilot/ardupilot/ArduCopter-stable/ArduCopter/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/ArduSub-stable/ArduSub/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/ArduPlane-stable/ArduPlane/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/APMrover2-stable/APMrover2/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/AntennaTracker/Parameters.cpp;" />
<add key="ParameterLocationsBleeding" value="https://raw.githubusercontent.com/ardupilot/ardupilot/master/ArduCopter/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/ArduSub/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/ArduPlane/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/APMrover2/Parameters.cpp; https://raw.githubusercontent.com/ardupilot/ardupilot/master/AntennaTracker/Parameters.cpp;" />
<add key="ParameterMetaDataXMLFileName" value="ParameterMetaData.xml" />
<add key="ParameterMetaDataXMLFileNameBackup" value="ParameterMetaDataBackup.xml" />
<add key="ClientId" value="zHTnuEq0RAWoLy5thcvTtMdwX7r6et2L3MAhxv8a0" />
<add key="ClientSecret" value="1ylYlXV4GuWJHIUywFg+XxE6hxsd3P/Dq5+J1PCUGxulC05/GC4Xpg==" />
<add key="AuthURL" value="https://auth.altitudeangel.com" />
<add key="APIURL" value="https://api.altitudeangel.com" />
<add key="ClientSettingsProvider.ServiceUri" value="" />
</appSettings>
找到之前添加的HikLogin(),找到如下代碼:
string DVRIPAddress = "192.168.0.64"; //設備IP地址或者域名
Int16 DVRPortNumber = 8000;//設備服務端口號
string DVRUserName = "admin";//設備登錄用戶名
string DVRPassword = "nanfoon51077533";//設備登錄密碼
更改爲:
string DVRIPAddress = ConfigurationManager.AppSettings["HikIP"]; //設備IP地址或者域名
Int16 DVRPortNumber = Int16.Parse( ConfigurationManager.AppSettings["HiPort"]);//設備服務端口號
string DVRUserName = ConfigurationManager.AppSettings["UserName"];//設備登錄用戶名
string DVRPassword = ConfigurationManager.AppSettings["PassWord"];//設備登錄密碼
實際運行效果:
6. 雙擊窗體彈出新界面
通過新建窗體來承載彈出的新視頻界面,彈出後陰藏地圖上的相機按鈕來防止用戶干擾,關閉彈出的窗口後返回至地圖頁顯示。
在FlightData.cs文件裏面的海康威視代碼區域增加圖像picturebox的雙擊事件函數:
private void PictureBoxHikVisionCameraOnMap_DoubleClick(object sender, System.EventArgs e)
{
}
返回到設計窗體選中海康的picturebox空間,在右下角的屬性中選中事件欄,找到doubleclick項,在下拉菜單裏面選中剛纔寫的事件函數名,鏈接事件。
代碼寫完之後如下:
/// <summary>
/// Double click event , to Pop the free moved Hik camera windows.
/// </summary>
/// <param name="sender"></param>
/// <param name="e"></param>
private void PictureBoxHikVisionCameraOnMap_DoubleClick(object sender, System.EventArgs e)
{
// CustomMessageBox.Show("Double click trigered"); // test the trigger event.
Form PupHikForm = new Form(); //creat the new from.
PupHikForm.ShowIcon = false;
PupHikForm.Text = "Flotilla-HikVision";
PupHikForm.FormClosed += new FormClosedEventHandler(PuphikForm_FormClosed); //the close event.
PictureBox PupHikFormPictureBox = new PictureBox();
PupHikFormPictureBox.BackColor = Color.DeepPink; // to test the Pic box.
PupHikFormPictureBox.Size = PupHikForm.Size;
//to auto size with the Form.
PupHikFormPictureBox.Anchor = ( AnchorStyles.Top|AnchorStyles.Bottom|AnchorStyles.Left|AnchorStyles.Right);
PupHikForm.Controls.Add(PupHikFormPictureBox); // Add the pic in form
ButtonCameraSwitch.PerformClick(); //close the on map picbox by trigger the button event mannuely.
HikLogin(); // Login again
HikPreview(PupHikFormPictureBox); //preview
ButtonCameraSwitch.Visible = false;
PupHikForm.Show();
}
/// <summary>
/// close event
/// </summary>
/// <param name="sender"></param>
/// <param name="e"></param>
private void PuphikForm_FormClosed(Object sender, FormClosedEventArgs e)
{
PictureBoxHikVisionCameraOnMap.Visible = true;
HikPreview(PictureBoxHikVisionCameraOnMap);//call it two times to avoid the logic conflict.
HikPreview(PictureBoxHikVisionCameraOnMap);
ButtonCameraSwitch.Visible = true;
}