Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Tools: add xacti-config application #25487

Merged
merged 1 commit into from
Apr 26, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
142 changes: 142 additions & 0 deletions Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
// =============================================================================
/**
* @file CX-GBXXXCtrl.cpp
* @brief CX-GBXXX用コントロールクラス ヘッダ
* @copyright (c) 2022 Xacti Corporation
*/
// =============================================================================

#include "CX-GBXXXCtrl.h"
#include <libusb-1.0/libusb.h>
#include <libuvc/libuvc.h>
#include <assert.h>

// -----------------------------------------------------------------------------
/*!
* @brief CX_GBXXXCtrlコンストラクタ
*/
// -----------------------------------------------------------------------------
CX_GBXXXCtrl::CX_GBXXXCtrl()
: m_ctx(NULL), m_dev(NULL), m_devh(NULL)
{
uvc_error_t res = uvc_init(&m_ctx, NULL);
if (res < 0)
{
uvc_perror(res, "uvc_init");
assert(res == 0);
}
}

// -----------------------------------------------------------------------------
/*!
* @brief CX_GBXXXCtrlデストラクタ
*/
// -----------------------------------------------------------------------------
CX_GBXXXCtrl::~CX_GBXXXCtrl()
{
uvc_exit(m_ctx);
}

// -----------------------------------------------------------------------------
/*!
* @brief カメラオープン
*
* @param [in] callback カメラシリアル番号(NULL: Don't Care)
*
* @return オープン成功可否
*/
// -----------------------------------------------------------------------------
bool CX_GBXXXCtrl::Open(const char *serial)
{
uvc_error_t res;
if ((res = uvc_find_device(
m_ctx, &m_dev,
0x296b, 0, serial)) < 0)
{
uvc_perror(res, "uvc_find_device"); // CX-GBXXX未接続
return false;
}

if ((res = uvc_open(m_dev, &m_devh)) < 0)
{
uvc_perror(res, "uvc_open");
return false;
}

return true;
}

// -----------------------------------------------------------------------------
/*!
* @brief カメラクローズ
*/
// -----------------------------------------------------------------------------
void CX_GBXXXCtrl::Close()
{
if (m_devh)
{
uvc_close(m_devh);
}
if (m_dev)
{
uvc_unref_device(m_dev);
}
}

// -----------------------------------------------------------------------------
/*!
* @brief カメラ情報設定
*
* @param [in] unit_id ユニットID
* @param [in] cotrol_id コントロールID
* @param [in] data データバッファ
* @param [in] length データサイズ(バイト)
*
* @return 成功可否
*/
// -----------------------------------------------------------------------------
bool CX_GBXXXCtrl::SetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length)
{
if (!m_devh)
{
uvc_perror(UVC_ERROR_INVALID_DEVICE, "SetCameraCtrl");
return false;
}

if (uvc_set_ctrl(m_devh, unit_id, cotrol_id, data, length) != length)
{
uvc_perror(UVC_ERROR_OTHER, "SetCameraCtrl");
return false;
}

return true;
}

// -----------------------------------------------------------------------------
/*!
* @brief カメラ情報取得
*
* @param [in] unit_id ユニットID
* @param [in] cotrol_id コントロールID
* @param [out] data データバッファ
* @param [in] length データサイズ(バイト)
*
* @return 成功可否
*/
// -----------------------------------------------------------------------------
bool CX_GBXXXCtrl::GetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length)
{
if (!m_devh)
{
uvc_perror(UVC_ERROR_INVALID_DEVICE, "GetCameraCtrl");
return false;
}

if (uvc_get_ctrl(m_devh, unit_id, cotrol_id, data, length, UVC_GET_CUR) != length)
{
uvc_perror(UVC_ERROR_OTHER, "GetCameraCtrl");
return false;
}

return true;
}
40 changes: 40 additions & 0 deletions Tools/cameras_gimbals/xacti-config/CX-GBXXXCtrl.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
// =============================================================================
/**
* @file CX-GBXXXCtrl.h
* @brief CX-GBXXX用コントロールクラス ヘッダ
* @copyright (c) 2022 Xacti Corporation
*/
// =============================================================================

#pragma once

#include <cstdint>

struct uvc_context;
typedef struct uvc_context uvc_context_t;
struct uvc_device;
typedef struct uvc_device uvc_device_t;
struct uvc_device_handle;
typedef struct uvc_device_handle uvc_device_handle_t;
struct uvc_frame;
typedef struct uvc_frame uvc_frame_t;

/*! @brief CCX_GBXXX用コントロールクラス */
class CX_GBXXXCtrl
{
public:
CX_GBXXXCtrl();
virtual ~CX_GBXXXCtrl();
bool Open(const char *serial);
void Close();

//! カメラコマンド
bool SetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length);
bool GetCameraCtrl(uint8_t unit_id, uint8_t cotrol_id, void *data, int length);

private:

uvc_context_t *m_ctx;
uvc_device_t *m_dev;
uvc_device_handle_t *m_devh;
};
48 changes: 48 additions & 0 deletions Tools/cameras_gimbals/xacti-config/Makefile
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
################################################################################
# Copyright (c) 2022, Xacti Corporation. All rights reserved.
# Modified by Randy Mackay
################################################################################

APP:= xacti-config
CC = g++

# Optimisation Options
#
CFLAGOPT =
CFLAGOPT += -O0

SRCS:= $(wildcard *.c) $(wildcard *.cpp)

INCS:= $(wildcard *.h)

PKGS:= x11

OBJS:= $(SRCS:.c=.o)
OBJS:= $(OBJS:.cpp=.o)

CFLAGS+= -g
CFLAGS+= $(CFLAGOPT)

LIBS+= -lm \
-Wl,-rpath \
-lpthread -pthread -luvc

CFLAGS+= `pkg-config --cflags $(PKGS)`

LIBS+= `pkg-config --libs $(PKGS)`

all: $(APP)

%.o: %.c $(INCS) Makefile
$(CC) -c -o $@ $(CFLAGS) $<
%.o: %.cpp $(INCS) Makefile
$(CC) -c -o $@ $(CFLAGS) $<

$(APP): $(OBJS) Makefile
$(CC) -o $(APP) $(OBJS) $(LIBS)

clean:
rm -rf $(OBJS) $(APP)

exec:
./$(APP)
23 changes: 23 additions & 0 deletions Tools/cameras_gimbals/xacti-config/README
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
********************
xacti-config
README
********************

Install Instructions

- download this program to your Linux/Ubuntu PC
- sudo apt-get install libusb-1.0-0-dev
- sudo apt install libuvc-dev
- make

Execution instructions

- sudo xacti-config option [value]
- the following options are available
--dronecan enable (value=1) or disable (value=0) dronecan parsing
--format format SD card
--help display usage
--irpalette set IR pallete (0:white hot, 1:black hot, 2:rainbow, 3:rainHC, 4:ironbow, 5:lava, 6:arctic, 7:glowbow, 8:graded fire, 9:hottest)
--msc change to mass storage class mode (for downloading from SD card)


99 changes: 99 additions & 0 deletions Tools/cameras_gimbals/xacti-config/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
#include <stdio.h>
#include <iostream>
#include <cstring>
#include "CX-GBXXXCtrl.h"

const char* this_app_str = "xacti-config";

// display help
void display_help()
{
printf("Usage: sudo %s option [value]\n", this_app_str);
printf(" --dronecan\tenable (value=1) or disable (value=0) dronecan parsing\n");
printf(" --format\tformat SD card\n");
printf(" --help\t\tdisplay usage\n");
printf(" --irpalette\t\tIR pallete (0:white hot, 1:black hot, 2:rainbow, 3:rainHC, 4:ironbow, 5:lava, 6:arctic, 7:glowbow, 8:graded fire, 9:hottest)\n");
printf(" --msc\t\tchange to mass storage class mode (for downloading from SD card)\n");
}

int main(int argc, char **argv)
{
// display help
if ((argc <= 1) || ((argc >= 2) && (strcmp(argv[1], "--help") == 0))) {
display_help();
return 0;
}

// open camera
CX_GBXXXCtrl camera_ctrl;
if (!camera_ctrl.Open(NULL)) {
printf("%s: failed to open camera\n", this_app_str);
return 1;
}

// args_ok set to true when command line processed correctly
bool args_ok = false;
bool ret_ok = true;

// enable DroneCAN
if ((argc >= 3) && (strcmp(argv[1], "--dronecan") == 0)) {
args_ok = true;
uint8_t enable = (strcmp(argv[2], "1") == 0);
ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x1e, &enable, sizeof(enable));
const char* enable_or_disable_str = enable ? "enable" : "disable";
if (ret_ok) {
printf("%s: %s DroneCAN\n", this_app_str, enable_or_disable_str);
} else {
printf("%s: failed to %s DroneCAN\n", this_app_str, enable_or_disable_str);
}
}

// format SD card
if ((argc >= 2) && (strcmp(argv[1], "--format") == 0)) {
args_ok = true;
uint8_t format_sd = 0;
ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x15, &format_sd, sizeof(format_sd));
if (ret_ok) {
printf("%s: formatted SD card\n", this_app_str);
} else {
printf("%s: failed format SD card\n", this_app_str);
}
}

// IR palette
if ((argc >= 3) && (strcmp(argv[1], "--irpalette") == 0)) {
args_ok = true;
int palette_int = 0;
sscanf(argv[2], "%d", &palette_int);
uint8_t palette_uint8 = (uint8_t)palette_int;
ret_ok = camera_ctrl.SetCameraCtrl(0x07, 0x19, &palette_uint8, sizeof(palette_uint8));
if (ret_ok) {
printf("%s: IR palette set to %d\n", this_app_str, (int)palette_uint8);
} else {
printf("%s: failed to set IR palette to %d\n", this_app_str, (int)palette_uint8);
}
}

// change to Mass Storage Mode to allow downloading of images and videos
if ((argc >= 2) && (strcmp(argv[1], "--msc") == 0)) {
args_ok = true;
uint8_t msc_mode = 1;
ret_ok = camera_ctrl.SetCameraCtrl(0x06, 0x07, &msc_mode, sizeof(msc_mode));
if (ret_ok) {
printf("%s: changed to mass storage mode\n", this_app_str);
} else {
printf("%s: failed to change to mass storage mode\n", this_app_str);
}
}

// close camera
camera_ctrl.Close();

// display help if args could not be processed
if (!args_ok) {
display_help();
}

// return 0 if OK, 1 if not OK
return ret_ok ? 0 : 1;
}