diff --git a/app/build.gradle b/app/build.gradle index 9589003..6550e05 100644 --- a/app/build.gradle +++ b/app/build.gradle @@ -72,7 +72,7 @@ dependencies { implementation 'com.squareup.okhttp3:okhttp:4.10.0' implementation 'com.squareup.okio:okio:3.2.0' implementation 'com.google.code.gson:gson:2.10.1' - + implementation(files("libs/mobile-ffmpeg.aar")) diff --git a/app/libs/mobile-ffmpeg.aar b/app/libs/mobile-ffmpeg.aar new file mode 100644 index 0000000..366ece1 Binary files /dev/null and b/app/libs/mobile-ffmpeg.aar differ diff --git a/app/src/main/java/com/example/longyi_groundstation/Main/Activity/MainActivity.java b/app/src/main/java/com/example/longyi_groundstation/Main/Activity/MainActivity.java index 987e0f8..b5e549c 100644 --- a/app/src/main/java/com/example/longyi_groundstation/Main/Activity/MainActivity.java +++ b/app/src/main/java/com/example/longyi_groundstation/Main/Activity/MainActivity.java @@ -8,6 +8,7 @@ import static android.view.View.VISIBLE; import static com.example.longyi_groundstation.MAVLink.enums.MAV_CMD.MAV_CMD_NAV_LAND; import static com.example.longyi_groundstation.MAVLink.enums.MAV_CMD.MAV_CMD_NAV_RETURN_TO_LAUNCH; import static com.example.longyi_groundstation.MAVLink.enums.MAV_CMD.MAV_CMD_NAV_TAKEOFF; +import static com.example.longyi_groundstation.Main.Void.AllVoid.rtsp_push; import static javax.xml.transform.OutputKeys.VERSION; import android.Manifest; @@ -39,6 +40,7 @@ import android.widget.TextView; import android.widget.Toast; import androidx.activity.EdgeToEdge; +import androidx.annotation.RequiresApi; import androidx.appcompat.app.AppCompatActivity; import androidx.core.app.ActivityCompat; import androidx.core.graphics.Insets; @@ -165,7 +167,7 @@ public class MainActivity extends AppCompatActivity { // 在成员变量部分添加 private CreateLinkAdapter createLinkAdapter; private List createLinkList = new ArrayList<>(); - private ArrayList selectedLinkList = new ArrayList<>();//当前选择的航线 + public static ArrayList selectedLinkList = new ArrayList<>();//当前选择的航线 private ArrayList uploadLinkList = new ArrayList<>();//当前上传的航线 public static boolean isUnlock = false;//是否解锁 public boolean isAdviseFly = true;//是否可以使用指点飞行 @@ -177,8 +179,10 @@ public class MainActivity extends AppCompatActivity { private Marker orangeMarker = null;//指点飞行图标 private int isAddOrEdit = 0;//0:添加 1:编辑 private Marker selectMarker;//当前选中的航点marker + private MainClick mainClick;//初始化点击事件的类 + @RequiresApi(api = Build.VERSION_CODES.O) @Override protected void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); @@ -211,6 +215,7 @@ public class MainActivity extends AppCompatActivity { * * @cuijingzhou */ + @RequiresApi(api = Build.VERSION_CODES.O) @SuppressLint("UnspecifiedRegisterReceiverFlag") private void initData() { // data = PrefsUtil.getUserObject(this, User.class); @@ -377,7 +382,17 @@ public class MainActivity extends AppCompatActivity { // 延迟初始化FPV视频流 allView.fpvWidget.post(() -> { - fpvVoid.setupFpvWidget(allView.fpvWidget, "rtsp://192.168.144.119/live"); + try { + fpvVoid.setupFpvWidget(allView.fpvWidget, "rtsp://192.168.144.119/live"); +// Thread.sleep(5000); +// Toast.makeText(this, "推送:" +// +rtsp_push.pushStreamToServer("rtsp://192.168.144.119/live", "rtmp://192.168.101.102:21935/live/stream_116?sign=hCuYagBHZQ"), Toast.LENGTH_SHORT).show(); + + }catch (Exception e){ + + } + + }); // 初始化FPV手势处理 @@ -634,17 +649,15 @@ public class MainActivity extends AppCompatActivity { // }); // //广播接收-setMissionAcklistener - myReceiver_MISSION_ACK.setMissionAcklistener(data -> { - Log.d(TAG, "myReceiver_MISSION_ACK: " + data.toString()); - }); -// -// //广播接收-setMissionAcklistener -// myReceiver_MISSION_CURRENT.setMissionCurrentlistener(data -> { -//// Log.d(TAG, "myReceiver_MISSION_CURRENT: " + data.toString()); -// allView.tv_test1.setText(data.optInt("seq") + ""); +// myReceiver_MISSION_ACK.setMissionAcklistener(data -> { +// Log.d(TAG, "myReceiver_MISSION_ACK: " + data.toString()); // }); - - +// + //广播接收-setMissionAcklistener + myReceiver_MISSION_CURRENT.setMissionCurrentlistener(data -> { +// Log.d(TAG, "myReceiver_MISSION_CURRENT: " + data.toString()); + allView.tv_test1.setText(data.optInt("seq") + ""); + }); } /** @@ -655,7 +668,7 @@ public class MainActivity extends AppCompatActivity { @SuppressLint({"NotifyDataSetChanged", "SetTextI18n", "DefaultLocale", "ClickableViewAccessibility"}) private void initOnClick() { // 创建MainClick实例 - MainClick mainClick = new MainClick(this, allView, mapVoid, flyVoid, tcpClient, + mainClick = new MainClick(this, allView, mapVoid, flyVoid, tcpClient, waypointMarkers, waypointPositions, createLinkList, selectedLinkList, uploadLinkList, createLinkAdapter, allLinkAdapter, sqlClass, mainMarker); @@ -715,6 +728,8 @@ public class MainActivity extends AppCompatActivity { allView.iv_ptz_left.setOnTouchListener(mainClick.getPTZTouchListener()); allView.iv_ptz_right.setOnTouchListener(mainClick.getPTZTouchListener()); allView.iv_ptz_bottom.setOnTouchListener(mainClick.getPTZTouchListener()); + allView.ll_PTZ_focus_amplify.setOnTouchListener(mainClick.getPTZTouchListener()); + allView.ll_PTZ_focus_reduce.setOnTouchListener(mainClick.getPTZTouchListener()); allView.ll_PTZ_amplify.setOnTouchListener(mainClick.getPTZTouchListener()); allView.ll_PTZ_reduce.setOnTouchListener(mainClick.getPTZTouchListener()); @@ -740,13 +755,11 @@ public class MainActivity extends AppCompatActivity { // 根据输入的文字模糊查询(名字)搜索框 allView.et_link_search.addTextChangedListener(mainClick.getTextWatcher()); + } - - // 在 MainActivity 中添加以下公共方法 - public void updateFlightPath() { if (flightPathPolyline != null) { flightPathPolyline.remove(); @@ -968,10 +981,9 @@ public class MainActivity extends AppCompatActivity { @Override public void onItemEditClick(int listId, int position) { isAddOrEdit = 1; - // 清除所有航点和航线 clearWaypoints(); - + mainClick.isSetLink = true; // 从数据库中获取选中的航线数据 selectedLinkList.addAll(sqlClass.getCreateLinkList(listId)); if (selectedLinkList.size() > 0) { diff --git a/app/src/main/java/com/example/longyi_groundstation/Main/Click/MainClick.java b/app/src/main/java/com/example/longyi_groundstation/Main/Click/MainClick.java index 1c3a883..ae56890 100644 --- a/app/src/main/java/com/example/longyi_groundstation/Main/Click/MainClick.java +++ b/app/src/main/java/com/example/longyi_groundstation/Main/Click/MainClick.java @@ -53,6 +53,7 @@ import static android.view.View.VISIBLE; import static com.example.longyi_groundstation.MAVLink.enums.MAV_CMD.MAV_CMD_NAV_LAND; import static com.example.longyi_groundstation.MAVLink.enums.MAV_CMD.MAV_CMD_NAV_RETURN_TO_LAUNCH; import static com.example.longyi_groundstation.MAVLink.enums.MAV_CMD.MAV_CMD_NAV_TAKEOFF; +import static com.example.longyi_groundstation.Main.Activity.MainActivity.selectedLinkList; public class MainClick implements View.OnClickListener { private MainActivity mainActivity; @@ -66,7 +67,7 @@ public class MainClick implements View.OnClickListener { private List waypointMarkers; private List waypointPositions; private List createLinkList; - private List selectedLinkList; +// private List selectedLinkList; private List uploadLinkList; private CreateLinkAdapter createLinkAdapter; private AllLinkAdapter allLinkAdapter; @@ -77,7 +78,7 @@ public class MainClick implements View.OnClickListener { // 其他变量 private int mainDisplay; - private boolean isSetLink; + public boolean isSetLink; private boolean isAdviseFly; private boolean isUnlock; private int isAddOrEdit; @@ -95,7 +96,6 @@ public class MainClick implements View.OnClickListener { this.waypointMarkers = waypointMarkers; this.waypointPositions = waypointPositions; this.createLinkList = createLinkList; - this.selectedLinkList = selectedLinkList; this.uploadLinkList = uploadLinkList; this.createLinkAdapter = createLinkAdapter; this.allLinkAdapter = allLinkAdapter; @@ -608,12 +608,14 @@ public class MainClick implements View.OnClickListener { // 更新航线显示 private void updateFlightPath() { - // 在MainActivity中实现,因为需要访问flightPathPolyline + // 调用MainActivity的updateFlightPath方法来更新航线显示 + mainActivity.updateFlightPath(); } // 在地图上显示航线 private void displayRouteOnMap(ArrayList createLinkList) { // 在MainActivity中实现,因为需要访问this.createLinkList + mainActivity.displayRouteOnMap(createLinkList); } // 添加或更新橘黄色marker @@ -689,10 +691,14 @@ public class MainClick implements View.OnClickListener { createLinkList.set(selectedIndex, updatedCreateLink); createLinkAdapter.setCreateLinkList(createLinkList); } + + // 更新航线显示 + updateFlightPath(); } }; } + // 获取FPV手势监听器 public FpvGestureHandler.OnFpvGestureListener getFpvGestureListener() { return new FpvGestureHandler.OnFpvGestureListener() { @@ -826,8 +832,10 @@ public class MainClick implements View.OnClickListener { handlePTZTouchDown(v); break; case MotionEvent.ACTION_UP: + handlePTZTouchUp(v); + break; case MotionEvent.ACTION_CANCEL: - handlePTZTouchUp(); + break; } return true; @@ -835,6 +843,7 @@ public class MainClick implements View.OnClickListener { }; } + // 处理PTZ触摸按下 private void handlePTZTouchDown(View v) { if (v == allView.iv_ptz_top) { @@ -886,15 +895,55 @@ public class MainClick implements View.OnClickListener { tcpClient.sendBytes(testData); } } + else if (v == allView.ll_PTZ_focus_amplify) { + Log.d("MainClick", "ll_PTZ_focus_amplify被按下"); + if (!tcpClient.isConnected()) { + Toast.makeText(mainActivity, "未连接到服务器", Toast.LENGTH_SHORT).show(); + } else { + byte[] testData = new byte[]{(byte) 0xFF, 0x01, 0x1D, 0x03, 0x00, 0x00, 0x21}; + tcpClient.sendBytes(testData); + } + } + else if (v == allView.ll_PTZ_focus_reduce) { + Log.d("MainClick", "ll_PTZ_focus_reduce被按下"); + if (!tcpClient.isConnected()) { + Toast.makeText(mainActivity, "未连接到服务器", Toast.LENGTH_SHORT).show(); + } else { + byte[] testData = new byte[]{(byte) 0xFF, 0x01, 0x1D, 0x02, 0x00, 0x00, 0x20}; + tcpClient.sendBytes(testData); + } + } } // 处理PTZ触摸抬起 - private void handlePTZTouchUp() { + private void handlePTZTouchUp(View v) { if (!tcpClient.isConnected()) { Toast.makeText(mainActivity, "未连接到服务器", Toast.LENGTH_SHORT).show(); } else { - byte[] testData1 = new byte[]{(byte) 0xFF, 0x01, 0x00, 0x60, 0x00, 0x00, 0x61}; - tcpClient.sendBytes(testData1); +// Toast.makeText(mainActivity, "结束", Toast.LENGTH_SHORT).show(); + if (v == allView.ll_PTZ_amplify) { + //变倍停止 + byte[] testData3 = new byte[]{(byte) 0xFF, 0x01, 0x00, 0x60, 0x00, 0x00, 0x61}; + tcpClient.sendBytes(testData3); + }else if (v == allView.ll_PTZ_reduce) { + //变倍停止 + byte[] testData3 = new byte[]{(byte) 0xFF, 0x01, 0x00, 0x60, 0x00, 0x00, 0x61}; + tcpClient.sendBytes(testData3); + }else if (v == allView.ll_PTZ_focus_amplify) { + //焦距停止 + byte[] testData3 = new byte[]{(byte) 0xFF, 0x01, 0x1D, 0x04, 0x00, 0x00, 0x22}; + tcpClient.sendBytes(testData3); + }else if (v == allView.ll_PTZ_focus_reduce) { + //焦距停止 + byte[] testData3 = new byte[]{(byte) 0xFF, 0x01, 0x1D, 0x04, 0x00, 0x00, 0x22}; + tcpClient.sendBytes(testData3); + }else { + //镜头停止 + byte[] testData1 = new byte[]{(byte) 0xFF, 0x01, 0x00, 0x00, 0x00, 0x00, 0x01}; + tcpClient.sendBytes(testData1); + } + + } } diff --git a/app/src/main/java/com/example/longyi_groundstation/Main/Service/MyBoundService.java b/app/src/main/java/com/example/longyi_groundstation/Main/Service/MyBoundService.java index f448fc9..31081b3 100644 --- a/app/src/main/java/com/example/longyi_groundstation/Main/Service/MyBoundService.java +++ b/app/src/main/java/com/example/longyi_groundstation/Main/Service/MyBoundService.java @@ -133,8 +133,8 @@ public class MyBoundService extends Service { // serialPortFinder = new SerialPortFinder(); //判断打开方式0:串口 1:UDP if (type == 0) { - serialHelper = new SerialHelper("/dev/ttyHS0", 115200) { -// serialHelper = new SerialHelper("/dev/ttyHS0", 57600) { +// serialHelper = new SerialHelper("/dev/ttyHS0", 115200) { + serialHelper = new SerialHelper("/dev/ttyHS0", 57600) { @Override protected void onDataReceived(final ComBean comBean) { // Log.d("cuijingzhou", Tool.bytesToHex(comBean.bRec)); @@ -160,7 +160,7 @@ public class MyBoundService extends Service { try { DatagramPacket packet = new DatagramPacket(buffer, buffer.length); serverSocket.receive(packet); - Log.d("cesssss", "接收数据: " + bytesToHex(packet.getData())); +// Log.d("cesssss", "接收数据: " + bytesToHex(packet.getData())); // 获取客户端IP和端口 InetAddress clientAddress = packet.getAddress(); @@ -453,7 +453,7 @@ public class MyBoundService extends Service { BroadcastUtil.Broadcast_MISSION_CURRENT(getApplication(), MsgList.get(MAVLINK_MSG_ID_MISSION_CURRENT)); } - Thread.sleep(50); + Thread.sleep(100); } } catch (Exception e) { @@ -493,10 +493,10 @@ public class MyBoundService extends Service { FlyVoid.setParamUpdateComplete(false); } - case MAVLINK_MSG_ID_MISSION_REQUEST: - if (MsgList.get(MAVLINK_MSG_ID_MISSION_REQUEST) != null) { - BroadcastUtil.Broadcast_MISSION_REQUEST(getApplication(), MsgList.get(MAVLINK_MSG_ID_MISSION_REQUEST)); - } +// case MAVLINK_MSG_ID_MISSION_REQUEST: +// if (MsgList.get(MAVLINK_MSG_ID_MISSION_REQUEST) != null) { +// BroadcastUtil.Broadcast_MISSION_REQUEST(getApplication(), MsgList.get(MAVLINK_MSG_ID_MISSION_REQUEST)); +// } case MAVLINK_MSG_ID_MISSION_COUNT: // Log.d(TAG, "wordT1: "); @@ -504,10 +504,10 @@ public class MyBoundService extends Service { BroadcastUtil.Broadcast_MISSION_REQUEST(getApplication(), MsgList.get(MAVLINK_MSG_ID_MISSION_REQUEST)); } - case MAVLINK_MSG_ID_MISSION_ACK: - if (MsgList.get(MAVLINK_MSG_ID_MISSION_ACK) != null) { - BroadcastUtil.Broadcast_MISSION_ACK(getApplication(), MsgList.get(MAVLINK_MSG_ID_MISSION_ACK)); - } +// case MAVLINK_MSG_ID_MISSION_ACK: +// if (MsgList.get(MAVLINK_MSG_ID_MISSION_ACK) != null) { +// BroadcastUtil.Broadcast_MISSION_ACK(getApplication(), MsgList.get(MAVLINK_MSG_ID_MISSION_ACK)); +// } default: // Log.d("cuijigzhou_msg_all_id", "不做处理:"+msg.msgid); diff --git a/app/src/main/java/com/example/longyi_groundstation/Main/Setting/Fragment/FoundationFragment.java b/app/src/main/java/com/example/longyi_groundstation/Main/Setting/Fragment/FoundationFragment.java index 8a2a81c..e064a05 100644 --- a/app/src/main/java/com/example/longyi_groundstation/Main/Setting/Fragment/FoundationFragment.java +++ b/app/src/main/java/com/example/longyi_groundstation/Main/Setting/Fragment/FoundationFragment.java @@ -203,10 +203,15 @@ public class FoundationFragment extends Fragment { * @cuijingzhou */ private void initText() { - setSelectedChannel(sp_low_end, Integer.parseInt(FlyVoid.paramList.get("FLTMODE1").getParam_value())); - setSelectedChannel(sp_mid_range, Integer.parseInt(FlyVoid.paramList.get("FLTMODE3").getParam_value())); - setSelectedChannel(sp_high_end, Integer.parseInt(FlyVoid.paramList.get("FLTMODE5").getParam_value())); - et_speed_text.setText(FlyVoid.paramList.get("WPNAV_SPEED").getParam_value()); + try { + et_speed_text.setText(FlyVoid.paramList.get("WPNAV_SPEED").getParam_value()); + setSelectedChannel(sp_low_end, Integer.parseInt(FlyVoid.paramList.get("FLTMODE1").getParam_value())); + setSelectedChannel(sp_mid_range, Integer.parseInt(FlyVoid.paramList.get("FLTMODE3").getParam_value())); + setSelectedChannel(sp_high_end, Integer.parseInt(FlyVoid.paramList.get("FLTMODE5").getParam_value())); + }catch (Exception e){ + Log.d("FLTMODE-initText", e.toString()); + } + } /** diff --git a/app/src/main/java/com/example/longyi_groundstation/Main/Void/AllVoid.java b/app/src/main/java/com/example/longyi_groundstation/Main/Void/AllVoid.java index 0773a72..7ff1654 100644 --- a/app/src/main/java/com/example/longyi_groundstation/Main/Void/AllVoid.java +++ b/app/src/main/java/com/example/longyi_groundstation/Main/Void/AllVoid.java @@ -1,15 +1,21 @@ package com.example.longyi_groundstation.Main.Void; +import android.os.Build; import android.util.Log; import android.widget.Toast; +import androidx.annotation.RequiresApi; + import com.example.longyi_groundstation.Main.Adapter.AllLinkAdapter; +import com.example.longyi_groundstation.Main.Void.RTSP.RTSP_push; import com.example.longyi_groundstation.Main.Void.XiangTuo.TcpClientUtil; import java.util.List; public class AllVoid { + public static RTSP_push rtsp_push = new RTSP_push(); + /** * 带重试机制的云台TCP连接方法 * 如果连接失败,等待5秒后重试,最多重试3次 @@ -20,6 +26,7 @@ public class AllVoid { * @param context 上下文对象,用于显示Toast提示 * @param tag 日志标签 */ + @RequiresApi(api = Build.VERSION_CODES.O) public static void connectToPTZWithRetry(TcpClientUtil tcpClient, String host, int port, android.content.Context context, String tag) { new Thread(() -> { int maxRetries = 3; @@ -31,7 +38,9 @@ public class AllVoid { tcpClient.connect(host, port); // 连接成功,跳出循环 ((android.app.Activity) context).runOnUiThread(() -> { - Toast.makeText(context, "云台连接成功", Toast.LENGTH_SHORT).show(); +// Toast.makeText(context, "云台连接成功", Toast.LENGTH_SHORT).show(); + byte[] testData = new byte[]{(byte) 0xFF, 0x01, 0x1D, 0x00, 0x00, 0x00, 0x1E}; + tcpClient.sendBytes(testData); }); break; } diff --git a/app/src/main/java/com/example/longyi_groundstation/Main/Void/RTSP/RTSP_push.java b/app/src/main/java/com/example/longyi_groundstation/Main/Void/RTSP/RTSP_push.java new file mode 100644 index 0000000..275d2af --- /dev/null +++ b/app/src/main/java/com/example/longyi_groundstation/Main/Void/RTSP/RTSP_push.java @@ -0,0 +1,190 @@ +package com.example.longyi_groundstation.Main.Void.RTSP; + +import android.util.Log; +import com.arthenica.mobileffmpeg.FFmpeg; +import com.arthenica.mobileffmpeg.ExecuteCallback; +import com.arthenica.mobileffmpeg.Config; +import com.arthenica.mobileffmpeg.Level; + +public class RTSP_push { + + private static final String TAG = "RTSP_push"; + private volatile boolean isStreaming = false; + private long executionId = -1; + + public RTSP_push() { + // 设置FFmpeg日志级别 + Config.enableLogCallback(logMessage -> { + switch (logMessage.getLevel()) { + case AV_LOG_DEBUG: + Log.d(TAG, logMessage.getText()); + break; + case AV_LOG_INFO: + Log.i(TAG, logMessage.getText()); + break; + case AV_LOG_WARNING: + Log.w(TAG, logMessage.getText()); + break; + case AV_LOG_ERROR: + Log.e(TAG, logMessage.getText()); + break; + default: + Log.v(TAG, logMessage.getText()); + break; + } + }); + Config.enableStatisticsCallback(statistics -> { + Log.d(TAG, String.format("frame: %d, time: %d, speed: %f", + statistics.getVideoFrameNumber(), + statistics.getTime(), + statistics.getSpeed())); + }); + } + + /** + * 将RTSP视频流推送到指定服务器 + * + * @param rtspUrl RTSP拉流地址 + * @param serverUrl 推送的目标服务器地址 + * @return 推流是否成功启动 + */ + public boolean pushStreamToServer(String rtspUrl, String serverUrl) { + try { + if (isStreaming) { + Log.w(TAG, "Already streaming, stopping current stream first"); + stopStreaming(); + } + + Log.d(TAG, "Starting to pull stream from: " + rtspUrl); + Log.d(TAG, "Pushing stream to server: " + serverUrl); + + // 构建优化的FFmpeg命令行参数 + String command = String.format( + "-rtsp_transport tcp -stimeout 5000000 -i %s " + + "-c copy -f flv %s", + rtspUrl, + serverUrl + ); + + // 使用Mobile-FFmpeg执行命令 + executeFFmpegWithMobileFFmpeg(command); + + return true; + } catch (Exception e) { + Log.e(TAG, "Failed to push stream: " + e.getMessage()); + return false; + } + } + + /** + * 使用Mobile-FFmpeg执行命令 + * + * @param command FFmpeg命令字符串 + */ + private void executeFFmpegWithMobileFFmpeg(String command) { + isStreaming = true; + Log.d(TAG, "Executing FFmpeg command: " + command); + + executionId = FFmpeg.executeAsync(command, new ExecuteCallback() { + @Override + public void apply(long executionId, int returnCode) { + Log.d(TAG, "FFmpeg process exited with code: " + returnCode); + isStreaming = false; + + if (returnCode == 0) { + Log.i(TAG, "FFmpeg command execution completed successfully."); + } else if (returnCode == 255) { + Log.w(TAG, "FFmpeg command execution cancelled."); + } else { + Log.e(TAG, "FFmpeg command execution failed with return code: " + returnCode); + String logs = Config.getLastCommandOutput(); + Log.e(TAG, "FFmpeg logs: " + logs); + } + } + }); + } + + /** + * 使用HTTP方式推送视频流(基于FFmpeg转封装) + * + * @param rtspUrl RTSP地址 + * @param serverUrl 目标服务器URL + * @return 是否推送成功启动 + */ + public boolean pushStreamViaHttp(String rtspUrl, String serverUrl) { + try { + if (isStreaming) { + Log.w(TAG, "Already streaming, stopping current stream first"); + stopStreaming(); + } + + Log.d(TAG, "Starting HTTP stream push from: " + rtspUrl); + Log.d(TAG, "Target server: " + serverUrl); + + // 使用FFmpeg将RTSP流转封装为MPEG-TS并通过HTTP推送 + String command = String.format( + "-rtsp_transport tcp -stimeout 5000000 -i %s -c copy -f mpegts " + + "-mpegts_flags +initial_discontinuity %s", + rtspUrl, + serverUrl + ); + + // 使用Mobile-FFmpeg执行命令 + executeFFmpegWithMobileFFmpeg(command); + + return true; + + } catch (Exception e) { + Log.e(TAG, "Error pushing stream via HTTP: " + e.getMessage()); + return false; + } + } + + /** + * 测试RTSP连接是否有效 + * + * @param rtspUrl RTSP地址 + * @return 是否连接成功 + */ + public boolean testRtspConnection(String rtspUrl) { + try { + Log.d(TAG, "Testing RTSP connection: " + rtspUrl); + String command = String.format("-rtsp_transport tcp -stimeout 5000000 -i %s -t 3 -f null -", rtspUrl); + int result = FFmpeg.execute(command); + return result == 0; + } catch (Exception e) { + Log.e(TAG, "Failed to test RTSP connection: " + e.getMessage()); + return false; + } + } + + /** + * 停止当前的推流任务 + */ + public void stopStreaming() { + Log.d(TAG, "Stopping stream push"); + isStreaming = false; + + if (executionId > 0) { + FFmpeg.cancel(executionId); + executionId = -1; + } + } + + /** + * 检查当前是否正在推流 + * + * @return 是否正在推流 + */ + public boolean isStreaming() { + return isStreaming; + } + + /** + * 释放资源 + */ + public void release() { + stopStreaming(); + Config.resetStatistics(); + } +} diff --git a/app/src/main/res/layout/activity_main.xml b/app/src/main/res/layout/activity_main.xml index 2ed4ce5..2d1c84b 100644 --- a/app/src/main/res/layout/activity_main.xml +++ b/app/src/main/res/layout/activity_main.xml @@ -914,7 +914,7 @@ android:gravity="center_horizontal" android:orientation="vertical" android:padding="5dp" - android:visibility="visible"> + android:visibility="gone"> + android:visibility="visible"> + android:src="@mipmap/icon_ptz_amplify" /> + android:visibility="visible"> + android:src="@mipmap/icon_ptz_reduce" /> + android:textSize="6sp" /> @@ -1572,7 +1572,7 @@ android:layout_marginTop="10dp" android:orientation="vertical" android:gravity="center" - android:visibility="visible"> + android:visibility="invisible"> - - -