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
23 changes: 23 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 @@ -63,6 +72,13 @@ message SpeedBody {
float z_m_s = 3; // Velocity in Z in metres/second.
}

// Speed type, represented in NED (North East Down) coordinates.
message SpeedNed {
float north_m_s = 1; // Velocity North in metres/second.
float east_m_s = 2; // Velocity East in metres/second.
float down_m_s = 3; // Velocity Down in metres/second.
}

// Angular velocity type
message AngularVelocityBody {
float roll_rad_s = 1; // Roll angular velocity in radians/second.
Expand Down Expand Up @@ -105,6 +121,13 @@ message VisionPositionEstimate {
Covariance pose_covariance = 4; // Pose cross-covariance matrix.
}

// Global speed estimate from a vision source.
message VisionSpeedEstimate {
uint64 time_usec = 1; // Timestamp UNIX Epoch time (0 to use Backend timestamp)
SpeedNed speed_ned = 2; // Global 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