Skip to content

Commit

Permalink
update get video stream example
Browse files Browse the repository at this point in the history
  • Loading branch information
duongGremsy committed Jan 4, 2023
1 parent af1d469 commit e22e351
Show file tree
Hide file tree
Showing 7 changed files with 80 additions and 158 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,6 @@ int main(int argc, char *argv[]){
printf("Starting LoadPayloadSettings example...\n");
signal(SIGINT,quit_handler);

// init thread to check receive message from payload
all_threads_init();

// create payloadsdk object
my_payload = new PayloadSdkInterface();

Expand All @@ -40,6 +37,9 @@ int main(int argc, char *argv[]){
}
}

// init thread to check receive message from payload
all_threads_init();

// request to read all settings of payload
my_payload->getPayloadCameraSettingList();

Expand Down
14 changes: 7 additions & 7 deletions src/examples/3._Set_Payload_Settings/set_payload_settings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,6 @@ int main(int argc, char *argv[]){
printf("Starting SetPayloadSettings example...\n");
signal(SIGINT,quit_handler);

// init thread to check receive message from payload
all_threads_init();

// create payloadsdk object
my_payload = new PayloadSdkInterface();

Expand All @@ -40,28 +37,31 @@ int main(int argc, char *argv[]){
}
}

// init thread to check receive message from payload
all_threads_init();

// change setting of RC_MODE to DUAL
my_payload->setPayloadCameraParam(PAYLOAD_CAMERA_RC_MODE, PAYLOAD_CAMERA_RC_MODE_DUAL, PARAM_TYPE_UINT32);

// change setting of OSD_MODE to STATUS to view Zoom factor
my_payload->setPayloadCameraParam(PAYLOAD_CAMERA_VIDEO_OSD_MODE, PAYLOAD_CAMERA_VIDEO_OSD_MODE_STATUS, PARAM_TYPE_UINT32);

// request to read all settings of payload, then check the RC_MODE setting
my_payload->getPayloadCameraSettingList();

bool is_zoom_in = false;
while(!time_to_exit){
// main loop, do some zooming commands
if(is_zoom_in){
my_payload->setPayloadCameraParam(PAYLOAD_CAMERA_VIDEO_ZOOM_SUPER_RESOLUTION_VALUE, 10000, PARAM_TYPE_UINT32);
printf("Zoom in to 10000 \n");
my_payload->setPayloadCameraParam(PAYLOAD_CAMERA_VIDEO_ZOOM_SUPER_RESOLUTION_VALUE, 21846, PARAM_TYPE_UINT32);
printf("Zoom in to 21846 \n");
}else{
my_payload->setPayloadCameraParam(PAYLOAD_CAMERA_VIDEO_ZOOM_SUPER_RESOLUTION_VALUE, 00000, PARAM_TYPE_UINT32);
printf("Zoom out to 00000 \n");
}
is_zoom_in = !is_zoom_in;

usleep(3000000); // sleep 3s
usleep(5000000); // sleep 5s
}


Expand Down
6 changes: 3 additions & 3 deletions src/examples/4._Capture_Image/capture_image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,6 @@ int main(int argc, char *argv[]){
printf("Starting CaptureImage example...\n");
signal(SIGINT,quit_handler);

// init thread to check receive message from payload
all_threads_init();

// create payloadsdk object
my_payload = new PayloadSdkInterface();

Expand All @@ -57,6 +54,9 @@ int main(int argc, char *argv[]){
}
}

// init thread to check receive message from payload
all_threads_init();

// set payload to video mode for testing
my_payload->setPayloadCameraMode(CAMERA_MODE_VIDEO);

Expand Down
6 changes: 3 additions & 3 deletions src/examples/5._Record_Video/record_video.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,6 @@ int main(int argc, char *argv[]){
printf("Starting RecordVideo example...\n");
signal(SIGINT,quit_handler);

// init thread to check receive message from payload
all_threads_init();

// create payloadsdk object
my_payload = new PayloadSdkInterface();

Expand All @@ -59,6 +56,9 @@ int main(int argc, char *argv[]){
}
}

// init thread to check receive message from payload
all_threads_init();

// set payload to video mode for testing
my_payload->setPayloadCameraMode(CAMERA_MODE_IMAGE);

Expand Down
70 changes: 43 additions & 27 deletions src/examples/6._Get_Video_Streaming/get_video_streaming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +51,6 @@ int main(int argc, char *argv[]){
printf("Starting GetStreaming example...\n");
signal(SIGINT,quit_handler);

// init thread to check receive message from payload
all_threads_init();

// create payloadsdk object
my_payload = new PayloadSdkInterface();

Expand All @@ -70,11 +67,16 @@ int main(int argc, char *argv[]){
printf("Payload connected! \n");
break;
}
usleep(10000);
}

// init thread to check receive message from payload
all_threads_init();

// change setting of VIDEO_OUT to BOTH_HDMI_UDP
printf("Change VideoOutput to both HDMI and Ethernet \n");
my_payload->setPayloadCameraParam(PAYLOAD_CAMERA_VIDEO_OUTPUT, PAYLOAD_CAMERA_VIDEO_OUTPUT_UDP, PARAM_TYPE_UINT32);
usleep(500000);

my_job = check_camera_info;
while(!time_to_exit){
Expand Down Expand Up @@ -145,32 +147,44 @@ void *payload_recv_handle(void *threadid)
{
// check payload messages
while(!time_to_exit){
if(my_payload != nullptr){
mavlink_message_t msg;
uint8_t msg_cnt = my_payload->getNewMewssage(msg);
if(msg_cnt){
printf("Got %d message in queue \n", msg_cnt);
printf(" --> message %d from system_id: %d with component_id: %d \n", msg.msgid, msg.sysid, msg.compid);
switch(msg.msgid){
case MAVLINK_MSG_ID_COMMAND_ACK:{
_handle_msg_command_ack(&msg);
break;
}
case MAVLINK_MSG_ID_CAMERA_INFORMATION:{
_handle_msg_camera_information(&msg);
break;
}
case MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION:{
_handle_msg_camera_stream_information(&msg);
#if 1
try{
if(my_payload != nullptr){
mavlink_message_t msg;
uint8_t msg_cnt = my_payload->getNewMewssage(msg);
// printf("message cnt: %d \n", msg_cnt);

if(msg_cnt){
// printf("Got %d message in queue \n", msg_cnt);
// printf(" --> message %d from system_id: %d with component_id: %d \n", msg.msgid, msg.sysid, msg.compid);
switch(msg.msgid){
case MAVLINK_MSG_ID_COMMAND_ACK:{
_handle_msg_command_ack(&msg);
break;
}
case MAVLINK_MSG_ID_CAMERA_INFORMATION:{
_handle_msg_camera_information(&msg);
break;
}
case MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION:{
_handle_msg_camera_stream_information(&msg);
break;
}
default: break;
}
}else{
// printf("Recieved message queue empty. \n");
}
default: break;
}
}else{

usleep(10000);
}else{
printf("My_payload nullptr \n");
}

usleep(10000);
}
}catch ( ... ) {};
#else
printf("thread running \n");
usleep(1000000);
#endif
}
pthread_exit(NULL);
}
Expand Down Expand Up @@ -205,6 +219,8 @@ void _handle_msg_camera_stream_information(mavlink_message_t* msg){

printf(" ---> Got streaming information: \n");
printf(" ---> Streaming type: %d \n", stream_info.type);
printf(" ---> Streaming resolution_v: %d \n", stream_info.resolution_v);
printf(" ---> Streaming resolution_h: %d \n", stream_info.resolution_h);
printf(" ---> Streaming name: %s \n", stream_info.name);
printf(" ---> Streaming uri: %s \n", stream_info.uri);

Expand Down Expand Up @@ -236,7 +252,7 @@ void *start_loop_thread(void *threadid)

string descr;
if(!_is_rtsp_stream){
descr = "udpsrc port=" + _stream_uri + " ! application/x-rtp,encoding-name=H264,payload=96 ! rtph264depay ! h264parse ! queue ! avdec_h264 ! nvvidconv ! nvoverlaysink"
descr = "udpsrc port=" + _stream_uri + " ! application/x-rtp,encoding-name=H264,payload=96 ! rtph264depay ! h264parse ! queue ! avdec_h264 ! nvvidconv ! nvoverlaysink sync=false async=false"
;
}else{
descr = "rtspsrc location=" + _stream_uri + " latency=0 ! rtph264depay ! h264parse ! nvv4l2decoder ! nvoverlaysink sync=false async=false";
Expand Down
3 changes: 3 additions & 0 deletions src/payloadSdkInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -229,6 +229,9 @@ getPayloadCameraInformation(){

mavlink_msg_command_long_encode_chan(SYS_ID, COMP_ID, port->get_mav_channel(), &message, &msg);

message.sysid = SYS_ID;
message.compid = COMP_ID;

// --------------------------------------------------------------------------
// WRITE
// --------------------------------------------------------------------------
Expand Down
Loading

0 comments on commit e22e351

Please sign in to comment.