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

mocap: add SetVisionSpeedEstimate #361

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
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
16 changes: 16 additions & 0 deletions protos/mocap/mocap.proto
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ option java_outer_classname = "MocapProto";
service MocapService {
// Send Global position/attitude estimate from a vision source.
rpc SetVisionPositionEstimate(SetVisionPositionEstimateRequest) returns(SetVisionPositionEstimateResponse) { option (mavsdk.options.async_type) = SYNC; }
// Send Global speed estimate from a vision source.
rpc SetVisionSpeedEstimate(SetVisionSpeedEstimateRequest) returns(SetVisionSpeedEstimateResponse) { option (mavsdk.options.async_type) = SYNC; }
// Send motion capture attitude and position.
rpc SetAttitudePositionMocap(SetAttitudePositionMocapRequest) returns(SetAttitudePositionMocapResponse) { option (mavsdk.options.async_type) = SYNC; }
// Send odometry information with an external interface.
Expand All @@ -28,6 +30,13 @@ message SetVisionPositionEstimateResponse {
MocapResult mocap_result = 1;
}

message SetVisionSpeedEstimateRequest {
VisionSpeedEstimate vision_speed_estimate = 1; // The vision speed estimate
}
message SetVisionSpeedEstimateResponse {
MocapResult mocap_result = 1;
}

message SetAttitudePositionMocapRequest {
AttitudePositionMocap attitude_position_mocap = 1; // The attitude and position data
}
Expand Down Expand Up @@ -105,6 +114,13 @@ message VisionPositionEstimate {
Covariance pose_covariance = 4; // Pose cross-covariance matrix.
}

// Global speed estimate from a vision source.
message VisionSpeedEstimate {
uint64 time_usec = 1; // PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp)
SpeedBody speed_body = 2; // Global speed (m/s)
Copy link
Collaborator

Choose a reason for hiding this comment

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

Just wondering on the frame here? When you see "Global" do you mean in North, East, Down, or Forward, Left, Down? I'm pretty sure "Body" would imply in body frame, so Forward, Left, Down.

Copy link
Author

@Luc-Meunier Luc-Meunier Jan 19, 2025

Choose a reason for hiding this comment

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

Hi @julianoes! Thanks for the review!

I used the same description as in the MAVLink doc, but I guess this is a typo.

However, I see in the VisionPositionEstimate a similar case:
PositionBody position_body = 2; // Global position (m)
Should I fix it too?

Copy link
Collaborator

Choose a reason for hiding this comment

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

Interesting. Might be worth checking what PX4 expects and whether we should update the MAVLink messages description.

Copy link
Collaborator

Choose a reason for hiding this comment

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

For position, PX4 expects NED:

https://github.com/PX4/PX4-Autopilot/blob/1eb9434b8c39fef3691684df520686231dce3939/src/modules/mavlink/mavlink_receiver.cpp#L1319C40-L1322

I don't see vision speed being used in PX4. How are you testing this?

Copy link
Author

Choose a reason for hiding this comment

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

Actually, we are currently testing with ArduPilot.
We used Intel RealSense T265 as an example (see https://ardupilot.org/copter/docs/common-vio-tracking-camera.html).

I suggest changing the "Global speed (m/s)" comment to "Body speed (m/s)"

Covariance speed_covariance = 3; // Linear velocity cross-covariance matrix.
}

// Motion capture attitude and position
message AttitudePositionMocap {
uint64 time_usec = 1; // PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp)
Expand Down
Loading