Skip to content

Commit

Permalink
just commit
Browse files Browse the repository at this point in the history
  • Loading branch information
duongGremsy committed Jan 6, 2023
1 parent e22e351 commit 7074a72
Show file tree
Hide file tree
Showing 9 changed files with 40 additions and 32 deletions.
2 changes: 1 addition & 1 deletion src/examples/1._Connect_to_Payload/connect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ int main(int argc, char *argv[]){
mavlink_message_t msg;
uint8_t msg_cnt = my_payload->getNewMewssage(msg);

if(msg_cnt && msg.sysid == 1 && msg.compid == MAV_COMP_ID_CAMERA6){
if(msg_cnt && msg.sysid == PAYLOAD_SYSTEM_ID && msg.compid == PAYLOAD_COMPONENT_ID){
printf("Payload connected! \n");
break;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ int main(int argc, char *argv[]){
mavlink_message_t msg;
uint8_t msg_cnt = my_payload->getNewMewssage(msg);

if(msg_cnt && msg.sysid == 1 && msg.compid == MAV_COMP_ID_CAMERA6){
if(msg_cnt && msg.sysid == PAYLOAD_SYSTEM_ID && msg.compid == PAYLOAD_COMPONENT_ID){
printf("Payload connected! \n");
break;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ int main(int argc, char *argv[]){
mavlink_message_t msg;
uint8_t msg_cnt = my_payload->getNewMewssage(msg);

if(msg_cnt && msg.sysid == 1 && msg.compid == MAV_COMP_ID_CAMERA6){
if(msg_cnt && msg.sysid == PAYLOAD_SYSTEM_ID && msg.compid == PAYLOAD_COMPONENT_ID){
printf("Payload connected! \n");
break;
}
Expand Down
2 changes: 1 addition & 1 deletion src/examples/4._Capture_Image/capture_image.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ int main(int argc, char *argv[]){
mavlink_message_t msg;
uint8_t msg_cnt = my_payload->getNewMewssage(msg);

if(msg_cnt && msg.sysid == 1 && msg.compid == MAV_COMP_ID_CAMERA6){
if(msg_cnt && msg.sysid == PAYLOAD_SYSTEM_ID && msg.compid == PAYLOAD_COMPONENT_ID){
printf("Payload connected! \n");
break;
}
Expand Down
2 changes: 1 addition & 1 deletion src/examples/5._Record_Video/record_video.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ int main(int argc, char *argv[]){
mavlink_message_t msg;
uint8_t msg_cnt = my_payload->getNewMewssage(msg);

if(msg_cnt && msg.sysid == 1 && msg.compid == MAV_COMP_ID_CAMERA6){
if(msg_cnt && msg.sysid == PAYLOAD_SYSTEM_ID && msg.compid == PAYLOAD_COMPONENT_ID){
printf("Payload connected! \n");
break;
}
Expand Down
7 changes: 5 additions & 2 deletions src/examples/6._Get_Video_Streaming/get_video_streaming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ int main(int argc, char *argv[]){
mavlink_message_t msg;
uint8_t msg_cnt = my_payload->getNewMewssage(msg);

if(msg_cnt && msg.sysid == 1 && msg.compid == MAV_COMP_ID_CAMERA6){
if(msg_cnt && msg.sysid == PAYLOAD_SYSTEM_ID && msg.compid == PAYLOAD_COMPONENT_ID){
printf("Payload connected! \n");
break;
}
Expand All @@ -75,7 +75,7 @@ int main(int argc, char *argv[]){

// 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);
my_payload->setPayloadCameraParam(PAYLOAD_CAMERA_VIDEO_OUTPUT, PAYLOAD_CAMERA_VIDEO_OUTPUT_BOTH, PARAM_TYPE_UINT32);
usleep(500000);

my_job = check_camera_info;
Expand Down Expand Up @@ -208,6 +208,9 @@ void _handle_msg_camera_information(mavlink_message_t* msg){
my_job = check_streaming_uri;
}else{
printf(" ---> Payload has no streaming video \n");
printf("It looks like your payload was setting to output video only to HDMI \n");
printf("I changed this payload settings: both HDMI and Ethernet.\n");
printf("Please reboot your payload to apply this setting. Then try again.\n");
my_job = idle;
}
}
Expand Down
48 changes: 24 additions & 24 deletions src/payloadSdkInterface.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#include "payloadSdkInterface.h"

PayloadSdkInterface::PayloadSdkInterface(){

printf("Starting Gremsy PayloadSdk %s\n", SDK_VERSION);
}

PayloadSdkInterface::~PayloadSdkInterface(){
Expand Down Expand Up @@ -64,7 +64,7 @@ moveGimbal(float pitch_spd, float yaw_spd){
msg.param2 = 0;
msg.param3 = yaw_spd;
msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.confirmation = 0;

// --------------------------------------------------------------------------
Expand Down Expand Up @@ -95,8 +95,8 @@ setPayloadCameraParam(char param_id[], uint32_t param_value, uint8_t param_type)
strcpy(msg.param_value, str.c_str());

msg.param_type = param_type;
msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;

// --------------------------------------------------------------------------
// ENCODE
Expand All @@ -118,8 +118,8 @@ PayloadSdkInterface::
getPayloadCameraSettingList(){
mavlink_param_ext_request_list_t msg= {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.trimmed = 0;

// --------------------------------------------------------------------------
Expand All @@ -142,8 +142,8 @@ PayloadSdkInterface::
getPayloadStorage(){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_REQUEST_STORAGE_INFORMATION;
msg.confirmation = 1;

Expand All @@ -167,8 +167,8 @@ PayloadSdkInterface::
getPayloadCaptureStatus(){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS;
msg.confirmation = 1;

Expand All @@ -192,8 +192,8 @@ PayloadSdkInterface::
getPayloadCameraMode(){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_REQUEST_CAMERA_SETTINGS;
msg.confirmation = 1;

Expand All @@ -217,8 +217,8 @@ PayloadSdkInterface::
getPayloadCameraInformation(){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_REQUEST_CAMERA_INFORMATION;
msg.confirmation = 1;

Expand All @@ -245,8 +245,8 @@ PayloadSdkInterface::
getPayloadCameraStreamingInformation(){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION;
msg.confirmation = 1;

Expand All @@ -270,8 +270,8 @@ PayloadSdkInterface::
setPayloadCameraMode(CAMERA_MODE mode){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_SET_CAMERA_MODE;
msg.param2 = (uint32_t)mode;
msg.confirmation = 1;
Expand All @@ -296,8 +296,8 @@ PayloadSdkInterface::
setPayloadCameraCaptureImage(){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_IMAGE_START_CAPTURE;
msg.confirmation = 1;

Expand All @@ -321,8 +321,8 @@ PayloadSdkInterface::
setPayloadCameraRecordVideoStart(){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_VIDEO_START_CAPTURE;
msg.confirmation = 1;

Expand All @@ -346,8 +346,8 @@ PayloadSdkInterface::
setPayloadCameraRecordVideoStop(){
mavlink_command_long_t msg = {0};

msg.target_system = 1;
msg.target_component = MAV_COMP_ID_CAMERA6;
msg.target_system = PAYLOAD_SYSTEM_ID;
msg.target_component = PAYLOAD_COMPONENT_ID;
msg.command = MAV_CMD_VIDEO_STOP_CAPTURE;
msg.confirmation = 1;

Expand Down
2 changes: 2 additions & 0 deletions src/payloadSdkInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
#include <iostream>
#include "payloadsdk.h"

#define SDK_VERSION "1.0.0_build.06Jan2023"

class PayloadSdkInterface
{

Expand Down
5 changes: 4 additions & 1 deletion src/payloadsdk.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,12 @@
#include "serial_port.h"
#include "udp_port.h"

#define PAYLOAD_SYSTEM_ID 1
#define PAYLOAD_COMPONENT_ID MAV_COMP_ID_CAMERA5

#define CONTROL_UART 0
#define CONTROL_UDP 1
#define CONTROL_METHOD CONTROL_UDP
#define CONTROL_METHOD CONTROL_UART

#define CAM_PARAM_ID_LEN 16
#define CAM_PARAM_VALUE_LEN 128
Expand Down

0 comments on commit 7074a72

Please sign in to comment.