Documentation ¶
Index ¶
- Variables
- func RegisterMocapServiceServer(s grpc.ServiceRegistrar, srv MocapServiceServer)
- type AngleBody
- func (*AngleBody) Descriptor() ([]byte, []int)deprecated
- func (x *AngleBody) GetPitchRad() float32
- func (x *AngleBody) GetRollRad() float32
- func (x *AngleBody) GetYawRad() float32
- func (*AngleBody) ProtoMessage()
- func (x *AngleBody) ProtoReflect() protoreflect.Message
- func (x *AngleBody) Reset()
- func (x *AngleBody) String() string
- type AngularVelocityBody
- func (*AngularVelocityBody) Descriptor() ([]byte, []int)deprecated
- func (x *AngularVelocityBody) GetPitchRadS() float32
- func (x *AngularVelocityBody) GetRollRadS() float32
- func (x *AngularVelocityBody) GetYawRadS() float32
- func (*AngularVelocityBody) ProtoMessage()
- func (x *AngularVelocityBody) ProtoReflect() protoreflect.Message
- func (x *AngularVelocityBody) Reset()
- func (x *AngularVelocityBody) String() string
- type AttitudePositionMocap
- func (*AttitudePositionMocap) Descriptor() ([]byte, []int)deprecated
- func (x *AttitudePositionMocap) GetPoseCovariance() *Covariance
- func (x *AttitudePositionMocap) GetPositionBody() *PositionBody
- func (x *AttitudePositionMocap) GetQ() *Quaternion
- func (x *AttitudePositionMocap) GetTimeUsec() uint64
- func (*AttitudePositionMocap) ProtoMessage()
- func (x *AttitudePositionMocap) ProtoReflect() protoreflect.Message
- func (x *AttitudePositionMocap) Reset()
- func (x *AttitudePositionMocap) String() string
- type Covariance
- type MocapResult
- func (*MocapResult) Descriptor() ([]byte, []int)deprecated
- func (x *MocapResult) GetResult() MocapResult_Result
- func (x *MocapResult) GetResultStr() string
- func (*MocapResult) ProtoMessage()
- func (x *MocapResult) ProtoReflect() protoreflect.Message
- func (x *MocapResult) Reset()
- func (x *MocapResult) String() string
- type MocapResult_Result
- func (MocapResult_Result) Descriptor() protoreflect.EnumDescriptor
- func (x MocapResult_Result) Enum() *MocapResult_Result
- func (MocapResult_Result) EnumDescriptor() ([]byte, []int)deprecated
- func (x MocapResult_Result) Number() protoreflect.EnumNumber
- func (x MocapResult_Result) String() string
- func (MocapResult_Result) Type() protoreflect.EnumType
- type MocapServiceClient
- type MocapServiceServer
- type Odometry
- func (*Odometry) Descriptor() ([]byte, []int)deprecated
- func (x *Odometry) GetAngularVelocityBody() *AngularVelocityBody
- func (x *Odometry) GetFrameId() Odometry_MavFrame
- func (x *Odometry) GetPoseCovariance() *Covariance
- func (x *Odometry) GetPositionBody() *PositionBody
- func (x *Odometry) GetQ() *Quaternion
- func (x *Odometry) GetSpeedBody() *SpeedBody
- func (x *Odometry) GetTimeUsec() uint64
- func (x *Odometry) GetVelocityCovariance() *Covariance
- func (*Odometry) ProtoMessage()
- func (x *Odometry) ProtoReflect() protoreflect.Message
- func (x *Odometry) Reset()
- func (x *Odometry) String() string
- type Odometry_MavFrame
- func (Odometry_MavFrame) Descriptor() protoreflect.EnumDescriptor
- func (x Odometry_MavFrame) Enum() *Odometry_MavFrame
- func (Odometry_MavFrame) EnumDescriptor() ([]byte, []int)deprecated
- func (x Odometry_MavFrame) Number() protoreflect.EnumNumber
- func (x Odometry_MavFrame) String() string
- func (Odometry_MavFrame) Type() protoreflect.EnumType
- type PositionBody
- func (*PositionBody) Descriptor() ([]byte, []int)deprecated
- func (x *PositionBody) GetXM() float32
- func (x *PositionBody) GetYM() float32
- func (x *PositionBody) GetZM() float32
- func (*PositionBody) ProtoMessage()
- func (x *PositionBody) ProtoReflect() protoreflect.Message
- func (x *PositionBody) Reset()
- func (x *PositionBody) String() string
- type Quaternion
- func (*Quaternion) Descriptor() ([]byte, []int)deprecated
- func (x *Quaternion) GetW() float32
- func (x *Quaternion) GetX() float32
- func (x *Quaternion) GetY() float32
- func (x *Quaternion) GetZ() float32
- func (*Quaternion) ProtoMessage()
- func (x *Quaternion) ProtoReflect() protoreflect.Message
- func (x *Quaternion) Reset()
- func (x *Quaternion) String() string
- type ServiceImpl
- func (s *ServiceImpl) SetAttitudePositionMocap(ctx context.Context, attitudePositionMocap *AttitudePositionMocap) (*SetAttitudePositionMocapResponse, error)
- func (s *ServiceImpl) SetOdometry(ctx context.Context, odometry *Odometry) (*SetOdometryResponse, error)
- func (s *ServiceImpl) SetVisionPositionEstimate(ctx context.Context, visionPositionEstimate *VisionPositionEstimate) (*SetVisionPositionEstimateResponse, error)
- type SetAttitudePositionMocapRequest
- func (*SetAttitudePositionMocapRequest) Descriptor() ([]byte, []int)deprecated
- func (x *SetAttitudePositionMocapRequest) GetAttitudePositionMocap() *AttitudePositionMocap
- func (*SetAttitudePositionMocapRequest) ProtoMessage()
- func (x *SetAttitudePositionMocapRequest) ProtoReflect() protoreflect.Message
- func (x *SetAttitudePositionMocapRequest) Reset()
- func (x *SetAttitudePositionMocapRequest) String() string
- type SetAttitudePositionMocapResponse
- func (*SetAttitudePositionMocapResponse) Descriptor() ([]byte, []int)deprecated
- func (x *SetAttitudePositionMocapResponse) GetMocapResult() *MocapResult
- func (*SetAttitudePositionMocapResponse) ProtoMessage()
- func (x *SetAttitudePositionMocapResponse) ProtoReflect() protoreflect.Message
- func (x *SetAttitudePositionMocapResponse) Reset()
- func (x *SetAttitudePositionMocapResponse) String() string
- type SetOdometryRequest
- func (*SetOdometryRequest) Descriptor() ([]byte, []int)deprecated
- func (x *SetOdometryRequest) GetOdometry() *Odometry
- func (*SetOdometryRequest) ProtoMessage()
- func (x *SetOdometryRequest) ProtoReflect() protoreflect.Message
- func (x *SetOdometryRequest) Reset()
- func (x *SetOdometryRequest) String() string
- type SetOdometryResponse
- func (*SetOdometryResponse) Descriptor() ([]byte, []int)deprecated
- func (x *SetOdometryResponse) GetMocapResult() *MocapResult
- func (*SetOdometryResponse) ProtoMessage()
- func (x *SetOdometryResponse) ProtoReflect() protoreflect.Message
- func (x *SetOdometryResponse) Reset()
- func (x *SetOdometryResponse) String() string
- type SetVisionPositionEstimateRequest
- func (*SetVisionPositionEstimateRequest) Descriptor() ([]byte, []int)deprecated
- func (x *SetVisionPositionEstimateRequest) GetVisionPositionEstimate() *VisionPositionEstimate
- func (*SetVisionPositionEstimateRequest) ProtoMessage()
- func (x *SetVisionPositionEstimateRequest) ProtoReflect() protoreflect.Message
- func (x *SetVisionPositionEstimateRequest) Reset()
- func (x *SetVisionPositionEstimateRequest) String() string
- type SetVisionPositionEstimateResponse
- func (*SetVisionPositionEstimateResponse) Descriptor() ([]byte, []int)deprecated
- func (x *SetVisionPositionEstimateResponse) GetMocapResult() *MocapResult
- func (*SetVisionPositionEstimateResponse) ProtoMessage()
- func (x *SetVisionPositionEstimateResponse) ProtoReflect() protoreflect.Message
- func (x *SetVisionPositionEstimateResponse) Reset()
- func (x *SetVisionPositionEstimateResponse) String() string
- type SpeedBody
- func (*SpeedBody) Descriptor() ([]byte, []int)deprecated
- func (x *SpeedBody) GetXMS() float32
- func (x *SpeedBody) GetYMS() float32
- func (x *SpeedBody) GetZMS() float32
- func (*SpeedBody) ProtoMessage()
- func (x *SpeedBody) ProtoReflect() protoreflect.Message
- func (x *SpeedBody) Reset()
- func (x *SpeedBody) String() string
- type UnimplementedMocapServiceServer
- func (UnimplementedMocapServiceServer) SetAttitudePositionMocap(context.Context, *SetAttitudePositionMocapRequest) (*SetAttitudePositionMocapResponse, error)
- func (UnimplementedMocapServiceServer) SetOdometry(context.Context, *SetOdometryRequest) (*SetOdometryResponse, error)
- func (UnimplementedMocapServiceServer) SetVisionPositionEstimate(context.Context, *SetVisionPositionEstimateRequest) (*SetVisionPositionEstimateResponse, error)
- type UnsafeMocapServiceServer
- type VisionPositionEstimate
- func (*VisionPositionEstimate) Descriptor() ([]byte, []int)deprecated
- func (x *VisionPositionEstimate) GetAngleBody() *AngleBody
- func (x *VisionPositionEstimate) GetPoseCovariance() *Covariance
- func (x *VisionPositionEstimate) GetPositionBody() *PositionBody
- func (x *VisionPositionEstimate) GetTimeUsec() uint64
- func (*VisionPositionEstimate) ProtoMessage()
- func (x *VisionPositionEstimate) ProtoReflect() protoreflect.Message
- func (x *VisionPositionEstimate) Reset()
- func (x *VisionPositionEstimate) String() string
Constants ¶
This section is empty.
Variables ¶
var ( Odometry_MavFrame_name = map[int32]string{ 0: "MAV_FRAME_MOCAP_NED", 1: "MAV_FRAME_LOCAL_FRD", } Odometry_MavFrame_value = map[string]int32{ "MAV_FRAME_MOCAP_NED": 0, "MAV_FRAME_LOCAL_FRD": 1, } )
Enum value maps for Odometry_MavFrame.
var ( MocapResult_Result_name = map[int32]string{ 0: "RESULT_UNKNOWN", 1: "RESULT_SUCCESS", 2: "RESULT_NO_SYSTEM", 3: "RESULT_CONNECTION_ERROR", 4: "RESULT_INVALID_REQUEST_DATA", 5: "RESULT_UNSUPPORTED", } MocapResult_Result_value = map[string]int32{ "RESULT_UNKNOWN": 0, "RESULT_SUCCESS": 1, "RESULT_NO_SYSTEM": 2, "RESULT_CONNECTION_ERROR": 3, "RESULT_INVALID_REQUEST_DATA": 4, "RESULT_UNSUPPORTED": 5, } )
Enum value maps for MocapResult_Result.
var File_mocap_proto protoreflect.FileDescriptor
var MocapService_ServiceDesc = grpc.ServiceDesc{ ServiceName: "mavsdk.rpc.mocap.MocapService", HandlerType: (*MocapServiceServer)(nil), Methods: []grpc.MethodDesc{ { MethodName: "SetVisionPositionEstimate", Handler: _MocapService_SetVisionPositionEstimate_Handler, }, { MethodName: "SetAttitudePositionMocap", Handler: _MocapService_SetAttitudePositionMocap_Handler, }, { MethodName: "SetOdometry", Handler: _MocapService_SetOdometry_Handler, }, }, Streams: []grpc.StreamDesc{}, Metadata: "mocap.proto", }
MocapService_ServiceDesc is the grpc.ServiceDesc for MocapService service. It's only intended for direct use with grpc.RegisterService, and not to be introspected or modified (even as a copy)
Functions ¶
func RegisterMocapServiceServer ¶
func RegisterMocapServiceServer(s grpc.ServiceRegistrar, srv MocapServiceServer)
Types ¶
type AngleBody ¶
type AngleBody struct { RollRad float32 `protobuf:"fixed32,1,opt,name=roll_rad,json=rollRad,proto3" json:"roll_rad,omitempty"` // Roll angle in radians. PitchRad float32 `protobuf:"fixed32,2,opt,name=pitch_rad,json=pitchRad,proto3" json:"pitch_rad,omitempty"` // Pitch angle in radians. YawRad float32 `protobuf:"fixed32,3,opt,name=yaw_rad,json=yawRad,proto3" json:"yaw_rad,omitempty"` // Yaw angle in radians. // contains filtered or unexported fields }
Body angle type
func (*AngleBody) Descriptor
deprecated
func (*AngleBody) GetPitchRad ¶
func (*AngleBody) GetRollRad ¶
func (*AngleBody) ProtoMessage ¶
func (*AngleBody) ProtoMessage()
func (*AngleBody) ProtoReflect ¶
func (x *AngleBody) ProtoReflect() protoreflect.Message
type AngularVelocityBody ¶
type AngularVelocityBody struct { RollRadS float32 `protobuf:"fixed32,1,opt,name=roll_rad_s,json=rollRadS,proto3" json:"roll_rad_s,omitempty"` // Roll angular velocity in radians/second. PitchRadS float32 `protobuf:"fixed32,2,opt,name=pitch_rad_s,json=pitchRadS,proto3" json:"pitch_rad_s,omitempty"` // Pitch angular velocity in radians/second. YawRadS float32 `protobuf:"fixed32,3,opt,name=yaw_rad_s,json=yawRadS,proto3" json:"yaw_rad_s,omitempty"` // Yaw angular velocity in radians/second. // contains filtered or unexported fields }
Angular velocity type
func (*AngularVelocityBody) Descriptor
deprecated
func (*AngularVelocityBody) Descriptor() ([]byte, []int)
Deprecated: Use AngularVelocityBody.ProtoReflect.Descriptor instead.
func (*AngularVelocityBody) GetPitchRadS ¶
func (x *AngularVelocityBody) GetPitchRadS() float32
func (*AngularVelocityBody) GetRollRadS ¶
func (x *AngularVelocityBody) GetRollRadS() float32
func (*AngularVelocityBody) GetYawRadS ¶
func (x *AngularVelocityBody) GetYawRadS() float32
func (*AngularVelocityBody) ProtoMessage ¶
func (*AngularVelocityBody) ProtoMessage()
func (*AngularVelocityBody) ProtoReflect ¶
func (x *AngularVelocityBody) ProtoReflect() protoreflect.Message
func (*AngularVelocityBody) Reset ¶
func (x *AngularVelocityBody) Reset()
func (*AngularVelocityBody) String ¶
func (x *AngularVelocityBody) String() string
type AttitudePositionMocap ¶
type AttitudePositionMocap struct { TimeUsec uint64 `protobuf:"varint,1,opt,name=time_usec,json=timeUsec,proto3" json:"time_usec,omitempty"` // PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp) Q *Quaternion `protobuf:"bytes,2,opt,name=q,proto3" json:"q,omitempty"` // Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) PositionBody *PositionBody `protobuf:"bytes,3,opt,name=position_body,json=positionBody,proto3" json:"position_body,omitempty"` // Body Position (NED) PoseCovariance *Covariance `protobuf:"bytes,4,opt,name=pose_covariance,json=poseCovariance,proto3" json:"pose_covariance,omitempty"` // Pose cross-covariance matrix. // contains filtered or unexported fields }
Motion capture attitude and position
func (*AttitudePositionMocap) Descriptor
deprecated
func (*AttitudePositionMocap) Descriptor() ([]byte, []int)
Deprecated: Use AttitudePositionMocap.ProtoReflect.Descriptor instead.
func (*AttitudePositionMocap) GetPoseCovariance ¶
func (x *AttitudePositionMocap) GetPoseCovariance() *Covariance
func (*AttitudePositionMocap) GetPositionBody ¶
func (x *AttitudePositionMocap) GetPositionBody() *PositionBody
func (*AttitudePositionMocap) GetQ ¶
func (x *AttitudePositionMocap) GetQ() *Quaternion
func (*AttitudePositionMocap) GetTimeUsec ¶
func (x *AttitudePositionMocap) GetTimeUsec() uint64
func (*AttitudePositionMocap) ProtoMessage ¶
func (*AttitudePositionMocap) ProtoMessage()
func (*AttitudePositionMocap) ProtoReflect ¶
func (x *AttitudePositionMocap) ProtoReflect() protoreflect.Message
func (*AttitudePositionMocap) Reset ¶
func (x *AttitudePositionMocap) Reset()
func (*AttitudePositionMocap) String ¶
func (x *AttitudePositionMocap) String() string
type Covariance ¶
type Covariance struct { CovarianceMatrix []float32 `protobuf:"fixed32,1,rep,packed,name=covariance_matrix,json=covarianceMatrix,proto3" json:"covariance_matrix,omitempty"` // The covariance matrix // contains filtered or unexported fields }
Covariance type. Row-major representation of a 6x6 cross-covariance matrix upper right triangle. Needs to be 21 entries or 1 entry with NaN if unknown.
func (*Covariance) Descriptor
deprecated
func (*Covariance) Descriptor() ([]byte, []int)
Deprecated: Use Covariance.ProtoReflect.Descriptor instead.
func (*Covariance) GetCovarianceMatrix ¶
func (x *Covariance) GetCovarianceMatrix() []float32
func (*Covariance) ProtoMessage ¶
func (*Covariance) ProtoMessage()
func (*Covariance) ProtoReflect ¶
func (x *Covariance) ProtoReflect() protoreflect.Message
func (*Covariance) Reset ¶
func (x *Covariance) Reset()
func (*Covariance) String ¶
func (x *Covariance) String() string
type MocapResult ¶
type MocapResult struct { Result MocapResult_Result `protobuf:"varint,1,opt,name=result,proto3,enum=mavsdk.rpc.mocap.MocapResult_Result" json:"result,omitempty"` // Result enum value ResultStr string `protobuf:"bytes,2,opt,name=result_str,json=resultStr,proto3" json:"result_str,omitempty"` // Human-readable English string describing the result // contains filtered or unexported fields }
Result type.
func (*MocapResult) Descriptor
deprecated
func (*MocapResult) Descriptor() ([]byte, []int)
Deprecated: Use MocapResult.ProtoReflect.Descriptor instead.
func (*MocapResult) GetResult ¶
func (x *MocapResult) GetResult() MocapResult_Result
func (*MocapResult) GetResultStr ¶
func (x *MocapResult) GetResultStr() string
func (*MocapResult) ProtoMessage ¶
func (*MocapResult) ProtoMessage()
func (*MocapResult) ProtoReflect ¶
func (x *MocapResult) ProtoReflect() protoreflect.Message
func (*MocapResult) Reset ¶
func (x *MocapResult) Reset()
func (*MocapResult) String ¶
func (x *MocapResult) String() string
type MocapResult_Result ¶
type MocapResult_Result int32
Possible results returned for mocap requests
const ( MocapResult_RESULT_UNKNOWN MocapResult_Result = 0 // Unknown error MocapResult_RESULT_SUCCESS MocapResult_Result = 1 // Request succeeded MocapResult_RESULT_NO_SYSTEM MocapResult_Result = 2 // No system is connected MocapResult_RESULT_CONNECTION_ERROR MocapResult_Result = 3 // Connection error MocapResult_RESULT_INVALID_REQUEST_DATA MocapResult_Result = 4 // Invalid request data MocapResult_RESULT_UNSUPPORTED MocapResult_Result = 5 // Function unsupported )
func (MocapResult_Result) Descriptor ¶
func (MocapResult_Result) Descriptor() protoreflect.EnumDescriptor
func (MocapResult_Result) Enum ¶
func (x MocapResult_Result) Enum() *MocapResult_Result
func (MocapResult_Result) EnumDescriptor
deprecated
func (MocapResult_Result) EnumDescriptor() ([]byte, []int)
Deprecated: Use MocapResult_Result.Descriptor instead.
func (MocapResult_Result) Number ¶
func (x MocapResult_Result) Number() protoreflect.EnumNumber
func (MocapResult_Result) String ¶
func (x MocapResult_Result) String() string
func (MocapResult_Result) Type ¶
func (MocapResult_Result) Type() protoreflect.EnumType
type MocapServiceClient ¶
type MocapServiceClient interface { // Send Global position/attitude estimate from a vision source. SetVisionPositionEstimate(ctx context.Context, in *SetVisionPositionEstimateRequest, opts ...grpc.CallOption) (*SetVisionPositionEstimateResponse, error) // Send motion capture attitude and position. SetAttitudePositionMocap(ctx context.Context, in *SetAttitudePositionMocapRequest, opts ...grpc.CallOption) (*SetAttitudePositionMocapResponse, error) // Send odometry information with an external interface. SetOdometry(ctx context.Context, in *SetOdometryRequest, opts ...grpc.CallOption) (*SetOdometryResponse, error) }
MocapServiceClient is the client API for MocapService service.
For semantics around ctx use and closing/ending streaming RPCs, please refer to https://pkg.go.dev/google.golang.org/grpc/?tab=doc#ClientConn.NewStream.
func NewMocapServiceClient ¶
func NewMocapServiceClient(cc grpc.ClientConnInterface) MocapServiceClient
type MocapServiceServer ¶
type MocapServiceServer interface { // Send Global position/attitude estimate from a vision source. SetVisionPositionEstimate(context.Context, *SetVisionPositionEstimateRequest) (*SetVisionPositionEstimateResponse, error) // Send motion capture attitude and position. SetAttitudePositionMocap(context.Context, *SetAttitudePositionMocapRequest) (*SetAttitudePositionMocapResponse, error) // Send odometry information with an external interface. SetOdometry(context.Context, *SetOdometryRequest) (*SetOdometryResponse, error) // contains filtered or unexported methods }
MocapServiceServer is the server API for MocapService service. All implementations must embed UnimplementedMocapServiceServer for forward compatibility
type Odometry ¶
type Odometry struct { TimeUsec uint64 `protobuf:"varint,1,opt,name=time_usec,json=timeUsec,proto3" json:"time_usec,omitempty"` // Timestamp (0 to use Backend timestamp). FrameId Odometry_MavFrame `protobuf:"varint,2,opt,name=frame_id,json=frameId,proto3,enum=mavsdk.rpc.mocap.Odometry_MavFrame" json:"frame_id,omitempty"` // Coordinate frame of reference for the pose data. PositionBody *PositionBody `protobuf:"bytes,3,opt,name=position_body,json=positionBody,proto3" json:"position_body,omitempty"` // Body Position. Q *Quaternion `protobuf:"bytes,4,opt,name=q,proto3" json:"q,omitempty"` // Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). SpeedBody *SpeedBody `protobuf:"bytes,5,opt,name=speed_body,json=speedBody,proto3" json:"speed_body,omitempty"` // Linear speed (m/s). AngularVelocityBody *AngularVelocityBody `protobuf:"bytes,6,opt,name=angular_velocity_body,json=angularVelocityBody,proto3" json:"angular_velocity_body,omitempty"` // Angular speed (rad/s). PoseCovariance *Covariance `protobuf:"bytes,7,opt,name=pose_covariance,json=poseCovariance,proto3" json:"pose_covariance,omitempty"` // Pose cross-covariance matrix. VelocityCovariance *Covariance `protobuf:"bytes,8,opt,name=velocity_covariance,json=velocityCovariance,proto3" json:"velocity_covariance,omitempty"` // Velocity cross-covariance matrix. // contains filtered or unexported fields }
Odometry message to communicate odometry information with an external interface.
func (*Odometry) Descriptor
deprecated
func (*Odometry) GetAngularVelocityBody ¶
func (x *Odometry) GetAngularVelocityBody() *AngularVelocityBody
func (*Odometry) GetFrameId ¶
func (x *Odometry) GetFrameId() Odometry_MavFrame
func (*Odometry) GetPoseCovariance ¶
func (x *Odometry) GetPoseCovariance() *Covariance
func (*Odometry) GetPositionBody ¶
func (x *Odometry) GetPositionBody() *PositionBody
func (*Odometry) GetQ ¶
func (x *Odometry) GetQ() *Quaternion
func (*Odometry) GetSpeedBody ¶
func (*Odometry) GetTimeUsec ¶
func (*Odometry) GetVelocityCovariance ¶
func (x *Odometry) GetVelocityCovariance() *Covariance
func (*Odometry) ProtoMessage ¶
func (*Odometry) ProtoMessage()
func (*Odometry) ProtoReflect ¶
func (x *Odometry) ProtoReflect() protoreflect.Message
type Odometry_MavFrame ¶
type Odometry_MavFrame int32
Mavlink frame id
const ( Odometry_MAV_FRAME_MOCAP_NED Odometry_MavFrame = 0 // MAVLink number: 14. Odometry local coordinate frame of data given by a motion capture system, Z-down (x: north, y: east, z: down). Odometry_MAV_FRAME_LOCAL_FRD Odometry_MavFrame = 1 // MAVLink number: 20. Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame). Replacement for MAV_FRAME_MOCAP_NED, MAV_FRAME_VISION_NED, MAV_FRAME_ESTIM_NED. )
func (Odometry_MavFrame) Descriptor ¶
func (Odometry_MavFrame) Descriptor() protoreflect.EnumDescriptor
func (Odometry_MavFrame) Enum ¶
func (x Odometry_MavFrame) Enum() *Odometry_MavFrame
func (Odometry_MavFrame) EnumDescriptor
deprecated
func (Odometry_MavFrame) EnumDescriptor() ([]byte, []int)
Deprecated: Use Odometry_MavFrame.Descriptor instead.
func (Odometry_MavFrame) Number ¶
func (x Odometry_MavFrame) Number() protoreflect.EnumNumber
func (Odometry_MavFrame) String ¶
func (x Odometry_MavFrame) String() string
func (Odometry_MavFrame) Type ¶
func (Odometry_MavFrame) Type() protoreflect.EnumType
type PositionBody ¶
type PositionBody struct { XM float32 `protobuf:"fixed32,1,opt,name=x_m,json=xM,proto3" json:"x_m,omitempty"` // X position in metres. YM float32 `protobuf:"fixed32,2,opt,name=y_m,json=yM,proto3" json:"y_m,omitempty"` // Y position in metres. ZM float32 `protobuf:"fixed32,3,opt,name=z_m,json=zM,proto3" json:"z_m,omitempty"` // Z position in metres. // contains filtered or unexported fields }
Body position type
func (*PositionBody) Descriptor
deprecated
func (*PositionBody) Descriptor() ([]byte, []int)
Deprecated: Use PositionBody.ProtoReflect.Descriptor instead.
func (*PositionBody) GetXM ¶
func (x *PositionBody) GetXM() float32
func (*PositionBody) GetYM ¶
func (x *PositionBody) GetYM() float32
func (*PositionBody) GetZM ¶
func (x *PositionBody) GetZM() float32
func (*PositionBody) ProtoMessage ¶
func (*PositionBody) ProtoMessage()
func (*PositionBody) ProtoReflect ¶
func (x *PositionBody) ProtoReflect() protoreflect.Message
func (*PositionBody) Reset ¶
func (x *PositionBody) Reset()
func (*PositionBody) String ¶
func (x *PositionBody) String() string
type Quaternion ¶
type Quaternion struct { W float32 `protobuf:"fixed32,1,opt,name=w,proto3" json:"w,omitempty"` // Quaternion entry 0, also denoted as a X float32 `protobuf:"fixed32,2,opt,name=x,proto3" json:"x,omitempty"` // Quaternion entry 1, also denoted as b Y float32 `protobuf:"fixed32,3,opt,name=y,proto3" json:"y,omitempty"` // Quaternion entry 2, also denoted as c Z float32 `protobuf:"fixed32,4,opt,name=z,proto3" json:"z,omitempty"` // Quaternion entry 3, also denoted as d // contains filtered or unexported fields }
Quaternion type.
All rotations and axis systems follow the right-hand rule. The Hamilton quaternion product definition is used. A zero-rotation quaternion is represented by (1,0,0,0). The quaternion could also be written as w + xi + yj + zk.
For more info see: https://en.wikipedia.org/wiki/Quaternion
func (*Quaternion) Descriptor
deprecated
func (*Quaternion) Descriptor() ([]byte, []int)
Deprecated: Use Quaternion.ProtoReflect.Descriptor instead.
func (*Quaternion) GetW ¶
func (x *Quaternion) GetW() float32
func (*Quaternion) GetX ¶
func (x *Quaternion) GetX() float32
func (*Quaternion) GetY ¶
func (x *Quaternion) GetY() float32
func (*Quaternion) GetZ ¶
func (x *Quaternion) GetZ() float32
func (*Quaternion) ProtoMessage ¶
func (*Quaternion) ProtoMessage()
func (*Quaternion) ProtoReflect ¶
func (x *Quaternion) ProtoReflect() protoreflect.Message
func (*Quaternion) Reset ¶
func (x *Quaternion) Reset()
func (*Quaternion) String ¶
func (x *Quaternion) String() string
type ServiceImpl ¶
type ServiceImpl struct {
Client MocapServiceClient
}
func (*ServiceImpl) SetAttitudePositionMocap ¶
func (s *ServiceImpl) SetAttitudePositionMocap(ctx context.Context, attitudePositionMocap *AttitudePositionMocap) (*SetAttitudePositionMocapResponse, error)
func (*ServiceImpl) SetOdometry ¶
func (s *ServiceImpl) SetOdometry(ctx context.Context, odometry *Odometry) (*SetOdometryResponse, error)
func (*ServiceImpl) SetVisionPositionEstimate ¶
func (s *ServiceImpl) SetVisionPositionEstimate(ctx context.Context, visionPositionEstimate *VisionPositionEstimate) (*SetVisionPositionEstimateResponse, error)
type SetAttitudePositionMocapRequest ¶
type SetAttitudePositionMocapRequest struct { AttitudePositionMocap *AttitudePositionMocap `` // The attitude and position data /* 126-byte string literal not displayed */ // contains filtered or unexported fields }
func (*SetAttitudePositionMocapRequest) Descriptor
deprecated
func (*SetAttitudePositionMocapRequest) Descriptor() ([]byte, []int)
Deprecated: Use SetAttitudePositionMocapRequest.ProtoReflect.Descriptor instead.
func (*SetAttitudePositionMocapRequest) GetAttitudePositionMocap ¶
func (x *SetAttitudePositionMocapRequest) GetAttitudePositionMocap() *AttitudePositionMocap
func (*SetAttitudePositionMocapRequest) ProtoMessage ¶
func (*SetAttitudePositionMocapRequest) ProtoMessage()
func (*SetAttitudePositionMocapRequest) ProtoReflect ¶
func (x *SetAttitudePositionMocapRequest) ProtoReflect() protoreflect.Message
func (*SetAttitudePositionMocapRequest) Reset ¶
func (x *SetAttitudePositionMocapRequest) Reset()
func (*SetAttitudePositionMocapRequest) String ¶
func (x *SetAttitudePositionMocapRequest) String() string
type SetAttitudePositionMocapResponse ¶
type SetAttitudePositionMocapResponse struct { MocapResult *MocapResult `protobuf:"bytes,1,opt,name=mocap_result,json=mocapResult,proto3" json:"mocap_result,omitempty"` // contains filtered or unexported fields }
func (*SetAttitudePositionMocapResponse) Descriptor
deprecated
func (*SetAttitudePositionMocapResponse) Descriptor() ([]byte, []int)
Deprecated: Use SetAttitudePositionMocapResponse.ProtoReflect.Descriptor instead.
func (*SetAttitudePositionMocapResponse) GetMocapResult ¶
func (x *SetAttitudePositionMocapResponse) GetMocapResult() *MocapResult
func (*SetAttitudePositionMocapResponse) ProtoMessage ¶
func (*SetAttitudePositionMocapResponse) ProtoMessage()
func (*SetAttitudePositionMocapResponse) ProtoReflect ¶
func (x *SetAttitudePositionMocapResponse) ProtoReflect() protoreflect.Message
func (*SetAttitudePositionMocapResponse) Reset ¶
func (x *SetAttitudePositionMocapResponse) Reset()
func (*SetAttitudePositionMocapResponse) String ¶
func (x *SetAttitudePositionMocapResponse) String() string
type SetOdometryRequest ¶
type SetOdometryRequest struct { Odometry *Odometry `protobuf:"bytes,1,opt,name=odometry,proto3" json:"odometry,omitempty"` // The odometry data // contains filtered or unexported fields }
func (*SetOdometryRequest) Descriptor
deprecated
func (*SetOdometryRequest) Descriptor() ([]byte, []int)
Deprecated: Use SetOdometryRequest.ProtoReflect.Descriptor instead.
func (*SetOdometryRequest) GetOdometry ¶
func (x *SetOdometryRequest) GetOdometry() *Odometry
func (*SetOdometryRequest) ProtoMessage ¶
func (*SetOdometryRequest) ProtoMessage()
func (*SetOdometryRequest) ProtoReflect ¶
func (x *SetOdometryRequest) ProtoReflect() protoreflect.Message
func (*SetOdometryRequest) Reset ¶
func (x *SetOdometryRequest) Reset()
func (*SetOdometryRequest) String ¶
func (x *SetOdometryRequest) String() string
type SetOdometryResponse ¶
type SetOdometryResponse struct { MocapResult *MocapResult `protobuf:"bytes,1,opt,name=mocap_result,json=mocapResult,proto3" json:"mocap_result,omitempty"` // contains filtered or unexported fields }
func (*SetOdometryResponse) Descriptor
deprecated
func (*SetOdometryResponse) Descriptor() ([]byte, []int)
Deprecated: Use SetOdometryResponse.ProtoReflect.Descriptor instead.
func (*SetOdometryResponse) GetMocapResult ¶
func (x *SetOdometryResponse) GetMocapResult() *MocapResult
func (*SetOdometryResponse) ProtoMessage ¶
func (*SetOdometryResponse) ProtoMessage()
func (*SetOdometryResponse) ProtoReflect ¶
func (x *SetOdometryResponse) ProtoReflect() protoreflect.Message
func (*SetOdometryResponse) Reset ¶
func (x *SetOdometryResponse) Reset()
func (*SetOdometryResponse) String ¶
func (x *SetOdometryResponse) String() string
type SetVisionPositionEstimateRequest ¶
type SetVisionPositionEstimateRequest struct { VisionPositionEstimate *VisionPositionEstimate `` // The vision position estimate /* 129-byte string literal not displayed */ // contains filtered or unexported fields }
func (*SetVisionPositionEstimateRequest) Descriptor
deprecated
func (*SetVisionPositionEstimateRequest) Descriptor() ([]byte, []int)
Deprecated: Use SetVisionPositionEstimateRequest.ProtoReflect.Descriptor instead.
func (*SetVisionPositionEstimateRequest) GetVisionPositionEstimate ¶
func (x *SetVisionPositionEstimateRequest) GetVisionPositionEstimate() *VisionPositionEstimate
func (*SetVisionPositionEstimateRequest) ProtoMessage ¶
func (*SetVisionPositionEstimateRequest) ProtoMessage()
func (*SetVisionPositionEstimateRequest) ProtoReflect ¶
func (x *SetVisionPositionEstimateRequest) ProtoReflect() protoreflect.Message
func (*SetVisionPositionEstimateRequest) Reset ¶
func (x *SetVisionPositionEstimateRequest) Reset()
func (*SetVisionPositionEstimateRequest) String ¶
func (x *SetVisionPositionEstimateRequest) String() string
type SetVisionPositionEstimateResponse ¶
type SetVisionPositionEstimateResponse struct { MocapResult *MocapResult `protobuf:"bytes,1,opt,name=mocap_result,json=mocapResult,proto3" json:"mocap_result,omitempty"` // contains filtered or unexported fields }
func (*SetVisionPositionEstimateResponse) Descriptor
deprecated
func (*SetVisionPositionEstimateResponse) Descriptor() ([]byte, []int)
Deprecated: Use SetVisionPositionEstimateResponse.ProtoReflect.Descriptor instead.
func (*SetVisionPositionEstimateResponse) GetMocapResult ¶
func (x *SetVisionPositionEstimateResponse) GetMocapResult() *MocapResult
func (*SetVisionPositionEstimateResponse) ProtoMessage ¶
func (*SetVisionPositionEstimateResponse) ProtoMessage()
func (*SetVisionPositionEstimateResponse) ProtoReflect ¶
func (x *SetVisionPositionEstimateResponse) ProtoReflect() protoreflect.Message
func (*SetVisionPositionEstimateResponse) Reset ¶
func (x *SetVisionPositionEstimateResponse) Reset()
func (*SetVisionPositionEstimateResponse) String ¶
func (x *SetVisionPositionEstimateResponse) String() string
type SpeedBody ¶
type SpeedBody struct { XMS float32 `protobuf:"fixed32,1,opt,name=x_m_s,json=xMS,proto3" json:"x_m_s,omitempty"` // Velocity in X in metres/second. YMS float32 `protobuf:"fixed32,2,opt,name=y_m_s,json=yMS,proto3" json:"y_m_s,omitempty"` // Velocity in Y in metres/second. ZMS float32 `protobuf:"fixed32,3,opt,name=z_m_s,json=zMS,proto3" json:"z_m_s,omitempty"` // Velocity in Z in metres/second. // contains filtered or unexported fields }
Speed type, represented in the Body (X Y Z) frame and in metres/second.
func (*SpeedBody) Descriptor
deprecated
func (*SpeedBody) ProtoMessage ¶
func (*SpeedBody) ProtoMessage()
func (*SpeedBody) ProtoReflect ¶
func (x *SpeedBody) ProtoReflect() protoreflect.Message
type UnimplementedMocapServiceServer ¶
type UnimplementedMocapServiceServer struct { }
UnimplementedMocapServiceServer must be embedded to have forward compatible implementations.
func (UnimplementedMocapServiceServer) SetAttitudePositionMocap ¶
func (UnimplementedMocapServiceServer) SetAttitudePositionMocap(context.Context, *SetAttitudePositionMocapRequest) (*SetAttitudePositionMocapResponse, error)
func (UnimplementedMocapServiceServer) SetOdometry ¶
func (UnimplementedMocapServiceServer) SetOdometry(context.Context, *SetOdometryRequest) (*SetOdometryResponse, error)
func (UnimplementedMocapServiceServer) SetVisionPositionEstimate ¶
func (UnimplementedMocapServiceServer) SetVisionPositionEstimate(context.Context, *SetVisionPositionEstimateRequest) (*SetVisionPositionEstimateResponse, error)
type UnsafeMocapServiceServer ¶
type UnsafeMocapServiceServer interface {
// contains filtered or unexported methods
}
UnsafeMocapServiceServer may be embedded to opt out of forward compatibility for this service. Use of this interface is not recommended, as added methods to MocapServiceServer will result in compilation errors.
type VisionPositionEstimate ¶
type VisionPositionEstimate struct { TimeUsec uint64 `protobuf:"varint,1,opt,name=time_usec,json=timeUsec,proto3" json:"time_usec,omitempty"` // PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp) PositionBody *PositionBody `protobuf:"bytes,2,opt,name=position_body,json=positionBody,proto3" json:"position_body,omitempty"` // Global position (m) AngleBody *AngleBody `protobuf:"bytes,3,opt,name=angle_body,json=angleBody,proto3" json:"angle_body,omitempty"` // Body angle (rad). PoseCovariance *Covariance `protobuf:"bytes,4,opt,name=pose_covariance,json=poseCovariance,proto3" json:"pose_covariance,omitempty"` // Pose cross-covariance matrix. // contains filtered or unexported fields }
Global position/attitude estimate from a vision source.
func (*VisionPositionEstimate) Descriptor
deprecated
func (*VisionPositionEstimate) Descriptor() ([]byte, []int)
Deprecated: Use VisionPositionEstimate.ProtoReflect.Descriptor instead.
func (*VisionPositionEstimate) GetAngleBody ¶
func (x *VisionPositionEstimate) GetAngleBody() *AngleBody
func (*VisionPositionEstimate) GetPoseCovariance ¶
func (x *VisionPositionEstimate) GetPoseCovariance() *Covariance
func (*VisionPositionEstimate) GetPositionBody ¶
func (x *VisionPositionEstimate) GetPositionBody() *PositionBody
func (*VisionPositionEstimate) GetTimeUsec ¶
func (x *VisionPositionEstimate) GetTimeUsec() uint64
func (*VisionPositionEstimate) ProtoMessage ¶
func (*VisionPositionEstimate) ProtoMessage()
func (*VisionPositionEstimate) ProtoReflect ¶
func (x *VisionPositionEstimate) ProtoReflect() protoreflect.Message
func (*VisionPositionEstimate) Reset ¶
func (x *VisionPositionEstimate) Reset()
func (*VisionPositionEstimate) String ¶
func (x *VisionPositionEstimate) String() string