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

Integrated Tusuav's gimbal driver and backend #28491

Open
wants to merge 8 commits into
base: master
Choose a base branch
from

Conversation

sunny-1987
Copy link

Tusuav Gimbal

Tusuav is a company specializing in the research and production of VTOLs,including the gimbals. The drive for its GT30 series gimbals has been added in these commits. The pods featured in this submission offer continuous zoom capability, EO camera and IR camera switching with picture-In-picture (PIP) functionality, target tracking, pan and tilt angle & rate control , photo-taking, video recording, and rangefinder up to 3km.

The protocol description

/*Field Index Bytes Description
-------------------------------------------------------------------------------------------
Header 0 1 0x5A
Length 1 1 total length, n=all bytes from byte5 to checksum, min=6, max=128
Flag 2 1 bit0-2: board id of the gimbal 0=main controller 1=comm board 2~4=motor pitch/roll/yaw
bit3: 1= need reply 0 = no need
bit4: 1= is a reply message 0 = now a reply message
bit5: 1= is a reading message 0 = is a writing message

Cmd 3 1 see details at below
Sub Cmd 4 1 see details at below
Data 5-n+1 n data in little endian lowest byte first
Checksum n+2 1 calculate_crc from mavlink 2.0 of byte from 0 to n+1 (inclusive)
*/

The website of Tusuav

https://www.tusuav.com/pod
image

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Oct 29, 2024
const char* AP_Mount_Tusuav::send_text_prefix = "Tusuav:";

// init - performs any required initialisation for this instance
// void AP_Mount_Tusuav::init()
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the PR! We normally don't allow commented out code to be added so could you remove this?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the feedback! We've removed the commented-out code as requested. Let us know if there’s anything else that needs adjustment

uint32_t now_ms = AP_HAL::millis();


if(now_ms - _last_update_ms_parse >= AP_MOUNT_TUSUAV_PARSE_INTERVAL_MS)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

small formatting issues here. There should be a space between the "if" and the bracket. Also the curly brace at the beginning of the next line should actually be on the end of this line

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the feedback! We've fixed the spacing issue with "if" and moved the curly brace. We've also checked and adjusted similar formatting issues throughout.

if(mnt_target.angle_rad.yaw_is_ef){
gimbal_angle_mode.mode.bits.yaw = static_cast<uint8_t>(GimbalAngleMode::Earth_Frame_Angle);
debug("euler:%f %f", gimbal_angle_mode.ef_angle[0], gimbal_angle_mode.ef_angle[2]);
}
Copy link
Contributor

@rmackay9 rmackay9 Oct 30, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

little white space issue here. The else should be on the same line as the previous curly bracket

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We've fixed this whitespace issue and reviewed similar formatting across the code to ensure consistency. Thank you!

}

case GimbalSubCmd::GimbalSubCmd_LaserDistance:{
// recieve laser rangefinder value in decimeters and save the value in meters
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

little white space issue here (too much indenting)

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for pointing that out! We've adjusted the indentation here and reviewed similar formatting throughout.

}
break;
}
default:break;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we normally separate these into two lines

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for your reply. I will make modifications based on your suggestions. Another question, can I continue submitting the modified code? Do I need to create a new pull request?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hi @sunny-1987,

feel free to keep updating this PR. No need to create a new one. By the way, if you think we're going to slow in reviewing, the best thing to do is post a comment asking that the PR be added to the weekly dev call. You can even attend if you like it is 8am Japan time each tuesday. If that's too early then there's an "EU Dev Call" on Wed at 4pm (Japan Time).

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hi! Could you let me know how to join the "EU Dev Call" on Wednesdays? Thanks!

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hi @sunny-1987, just join ArduPilot's discord server and then go to the "weekly-devcall" voice channel at 4pm Japan time today.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ok,thanks.

Copy link
Contributor

@timtuxworth timtuxworth Nov 15, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What is your discord handle @sunny-1987 ? I'd like to try to contact you while I'm in China. I'm "timtuxworth" on WeChat/WeiXin.

@rmackay9
Copy link
Contributor

Thanks very much for this. In general it looks like it's well written.

It might be good to send me a gimbal so that I can properly test it and confirm that all the features are working. That's not completely necessary though, so no pressure.

By the way, I see there is a "merge" commit in there which we normally don't merge. It would be good to get rid of this by rebasing on master.

@@ -60,6 +60,10 @@
#define HAL_MOUNT_TOPOTEK_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED
#endif

#ifndef HAL_MOUNT_TUSUAV_ENABLED
#define HAL_MOUNT_TUSUAV_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a big chunk of code, enabled by default probably needs to be a bit more nuanced

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree, the flash cost will likely be the biggest issue in getting this merged. There are certainly things we can do to share more code amonst the various gimbals but whether we need to do that before this gets merged or not is a good question

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

file.zip
We evaluated the flash storage conditions before and after implementing AP_Mount_Tusuav, and the results are attached. Additionally, we have included a video demonstrating our gimbal functionality, and we are using the CubeOrangePlus flight controller.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

fyi, we have several CI tests below that check sizes for several classes of autopilot

Comment on lines 1 to 2
#include "AP_Mount_Tusuav.h"
#if HAL_MOUNT_TUSUAV_ENABLED
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
#include "AP_Mount_Tusuav.h"
#if HAL_MOUNT_TUSUAV_ENABLED
#include "AP_Mount_config.h"
#if HAL_MOUNT_TUSUAV_ENABLED
#include "AP_Mount_Tusuav.h"

Comment on lines 27 to 28
#include "AP_Mount_Backend_Serial.h"

#if HAL_MOUNT_TUSUAV_ENABLED
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
#include "AP_Mount_Backend_Serial.h"
#if HAL_MOUNT_TUSUAV_ENABLED
#include "AP_Mount_config.h"
#if HAL_MOUNT_TUSUAV_ENABLED
#include "AP_Mount_Backend_Serial.h"

Comment on lines 48 to 50
// // init - performs any required initialisation for this instance
// void init() override;

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// // init - performs any required initialisation for this instance
// void init() override;


// get attitude as a quaternion. returns true on success
bool get_attitude_quaternion(Quaternion& att_quat) override;
private:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
private:
private:

enum class GimbalSubCmd : uint8_t {
GimbalSubCmd_GimbalAngle = 0x16, // retrieve gimbal angles
GimbalSubCmd_PlaneSensor_Attitude = 0x18, // send plane sensor & attitude to gimbal
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Seems to be some oddity in naming here.

Perhaps this enum should just be Cmd?

Or strip some component out of the entries?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for your comments! The GimbalSubCmd enum represents sub-commands linked to MasCmd_Gimbal = 0xBD in the GimbalCmd enum. It defines specific operations for controlling and retrieving gimbal status, including angle retrieval, sensor attitude synchronization, parameter adjustments, laser measurement retrieval, and zoom or tracking configurations. We have reviewed the GimbalSubCmd entries and confirmed that each one is essential for its respective function.

return false;
}

int32_t int_zoom_value = (int32_t)zoom_value;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
int32_t int_zoom_value = (int32_t)zoom_value;
const int32_t int_zoom_value = (int32_t)zoom_value;

... and in general just const everything that can be in here

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for the suggestion. We’ve updated the code to apply 'const' where applicable.


int32_t int_zoom_value = (int32_t)zoom_value;
int16_t speed = AP_MOUNT_TUSUAV_ZOOM_SPEED;
if (zoom_type == ZoomType::RATE) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

switch

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you!

}

default:{
return 0;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
return 0;
return false;

return false;
}

MessageCameraSource camera = {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
MessageCameraSource camera = {
const MessageCameraSource camera{

... any many other places

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok,thank you!

};

FrameType frame_to_send{
.flag={0},
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

indenting

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

6 participants