Skip to content

Commit

Permalink
mocap: add SetVisionSpeedEstimate
Browse files Browse the repository at this point in the history
Co-authored-by: miodine <[email protected]>
  • Loading branch information
Luc-Meunier and miodine committed Jan 23, 2025
1 parent 9a871c7 commit bef683a
Showing 1 changed file with 23 additions and 0 deletions.
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

0 comments on commit bef683a

Please sign in to comment.