rcl_interfaces_msg

package
v0.0.0-...-f3704aa Latest Latest
Warning

This package is not in the latest version of its module.

Go to latest
Published: Oct 8, 2021 License: Apache-2.0 Imports: 6 Imported by: 0

Documentation

Index

Constants

View Source
const (
	Log_DEBUG byte = 10 // Debug is for pedantic information, which is useful when debugging issues.
	Log_INFO  byte = 20 // Info is the standard informational level and is used to report expectedinformation.
	Log_WARN  byte = 30 // Warning is for information that may potentially cause issues or possibly unexpectedbehavior.
	Log_ERROR byte = 40 // Error is for information that this node cannot resolve.
	Log_FATAL byte = 50 // Information about a impending node shutdown.
)
View Source
const (
	ParameterType_PARAMETER_NOT_SET       uint8 = 0 // Default value, which implies this is not a valid parameter.
	ParameterType_PARAMETER_BOOL          uint8 = 1
	ParameterType_PARAMETER_INTEGER       uint8 = 2
	ParameterType_PARAMETER_DOUBLE        uint8 = 3
	ParameterType_PARAMETER_STRING        uint8 = 4
	ParameterType_PARAMETER_BYTE_ARRAY    uint8 = 5
	ParameterType_PARAMETER_BOOL_ARRAY    uint8 = 6
	ParameterType_PARAMETER_INTEGER_ARRAY uint8 = 7
	ParameterType_PARAMETER_DOUBLE_ARRAY  uint8 = 8
	ParameterType_PARAMETER_STRING_ARRAY  uint8 = 9
)

Variables

View Source
var FloatingPointRangeTypeSupport types.MessageTypeSupport = _FloatingPointRangeTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var IntegerRangeTypeSupport types.MessageTypeSupport = _IntegerRangeTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var ListParametersResultTypeSupport types.MessageTypeSupport = _ListParametersResultTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var LogTypeSupport types.MessageTypeSupport = _LogTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var ParameterDescriptorTypeSupport types.MessageTypeSupport = _ParameterDescriptorTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var ParameterEventDescriptorsTypeSupport types.MessageTypeSupport = _ParameterEventDescriptorsTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var ParameterEventTypeSupport types.MessageTypeSupport = _ParameterEventTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var ParameterTypeSupport types.MessageTypeSupport = _ParameterTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var ParameterTypeTypeSupport types.MessageTypeSupport = _ParameterTypeTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var ParameterValueTypeSupport types.MessageTypeSupport = _ParameterValueTypeSupport{}

Modifying this variable is undefined behavior.

View Source
var SetParametersResultTypeSupport types.MessageTypeSupport = _SetParametersResultTypeSupport{}

Modifying this variable is undefined behavior.

Functions

func CloneFloatingPointRangeSlice

func CloneFloatingPointRangeSlice(dst, src []FloatingPointRange)

CloneFloatingPointRangeSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneIntegerRangeSlice

func CloneIntegerRangeSlice(dst, src []IntegerRange)

CloneIntegerRangeSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneListParametersResultSlice

func CloneListParametersResultSlice(dst, src []ListParametersResult)

CloneListParametersResultSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneLogSlice

func CloneLogSlice(dst, src []Log)

CloneLogSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneParameterDescriptorSlice

func CloneParameterDescriptorSlice(dst, src []ParameterDescriptor)

CloneParameterDescriptorSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneParameterEventDescriptorsSlice

func CloneParameterEventDescriptorsSlice(dst, src []ParameterEventDescriptors)

CloneParameterEventDescriptorsSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneParameterEventSlice

func CloneParameterEventSlice(dst, src []ParameterEvent)

CloneParameterEventSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneParameterSlice

func CloneParameterSlice(dst, src []Parameter)

CloneParameterSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneParameterTypeSlice

func CloneParameterTypeSlice(dst, src []ParameterType)

CloneParameterTypeSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneParameterValueSlice

func CloneParameterValueSlice(dst, src []ParameterValue)

CloneParameterValueSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func CloneSetParametersResultSlice

func CloneSetParametersResultSlice(dst, src []SetParametersResult)

CloneSetParametersResultSlice clones src to dst by calling Clone for each element in src. Panics if len(dst) < len(src).

func FloatingPointRange__Array_to_C

func FloatingPointRange__Array_to_C(cSlice []CFloatingPointRange, goSlice []FloatingPointRange)

func FloatingPointRange__Array_to_Go

func FloatingPointRange__Array_to_Go(goSlice []FloatingPointRange, cSlice []CFloatingPointRange)

func FloatingPointRange__Sequence_to_C

func FloatingPointRange__Sequence_to_C(cSlice *CFloatingPointRange__Sequence, goSlice []FloatingPointRange)

func FloatingPointRange__Sequence_to_Go

func FloatingPointRange__Sequence_to_Go(goSlice *[]FloatingPointRange, cSlice CFloatingPointRange__Sequence)

func IntegerRange__Array_to_C

func IntegerRange__Array_to_C(cSlice []CIntegerRange, goSlice []IntegerRange)

func IntegerRange__Array_to_Go

func IntegerRange__Array_to_Go(goSlice []IntegerRange, cSlice []CIntegerRange)

func IntegerRange__Sequence_to_C

func IntegerRange__Sequence_to_C(cSlice *CIntegerRange__Sequence, goSlice []IntegerRange)

func IntegerRange__Sequence_to_Go

func IntegerRange__Sequence_to_Go(goSlice *[]IntegerRange, cSlice CIntegerRange__Sequence)

func ListParametersResult__Array_to_C

func ListParametersResult__Array_to_C(cSlice []CListParametersResult, goSlice []ListParametersResult)

func ListParametersResult__Array_to_Go

func ListParametersResult__Array_to_Go(goSlice []ListParametersResult, cSlice []CListParametersResult)

func ListParametersResult__Sequence_to_C

func ListParametersResult__Sequence_to_C(cSlice *CListParametersResult__Sequence, goSlice []ListParametersResult)

func ListParametersResult__Sequence_to_Go

func ListParametersResult__Sequence_to_Go(goSlice *[]ListParametersResult, cSlice CListParametersResult__Sequence)

func Log__Array_to_C

func Log__Array_to_C(cSlice []CLog, goSlice []Log)

func Log__Array_to_Go

func Log__Array_to_Go(goSlice []Log, cSlice []CLog)

func Log__Sequence_to_C

func Log__Sequence_to_C(cSlice *CLog__Sequence, goSlice []Log)

func Log__Sequence_to_Go

func Log__Sequence_to_Go(goSlice *[]Log, cSlice CLog__Sequence)

func ParameterDescriptor__Array_to_C

func ParameterDescriptor__Array_to_C(cSlice []CParameterDescriptor, goSlice []ParameterDescriptor)

func ParameterDescriptor__Array_to_Go

func ParameterDescriptor__Array_to_Go(goSlice []ParameterDescriptor, cSlice []CParameterDescriptor)

func ParameterDescriptor__Sequence_to_C

func ParameterDescriptor__Sequence_to_C(cSlice *CParameterDescriptor__Sequence, goSlice []ParameterDescriptor)

func ParameterDescriptor__Sequence_to_Go

func ParameterDescriptor__Sequence_to_Go(goSlice *[]ParameterDescriptor, cSlice CParameterDescriptor__Sequence)

func ParameterEventDescriptors__Array_to_C

func ParameterEventDescriptors__Array_to_C(cSlice []CParameterEventDescriptors, goSlice []ParameterEventDescriptors)

func ParameterEventDescriptors__Array_to_Go

func ParameterEventDescriptors__Array_to_Go(goSlice []ParameterEventDescriptors, cSlice []CParameterEventDescriptors)

func ParameterEventDescriptors__Sequence_to_C

func ParameterEventDescriptors__Sequence_to_C(cSlice *CParameterEventDescriptors__Sequence, goSlice []ParameterEventDescriptors)

func ParameterEventDescriptors__Sequence_to_Go

func ParameterEventDescriptors__Sequence_to_Go(goSlice *[]ParameterEventDescriptors, cSlice CParameterEventDescriptors__Sequence)

func ParameterEvent__Array_to_C

func ParameterEvent__Array_to_C(cSlice []CParameterEvent, goSlice []ParameterEvent)

func ParameterEvent__Array_to_Go

func ParameterEvent__Array_to_Go(goSlice []ParameterEvent, cSlice []CParameterEvent)

func ParameterEvent__Sequence_to_C

func ParameterEvent__Sequence_to_C(cSlice *CParameterEvent__Sequence, goSlice []ParameterEvent)

func ParameterEvent__Sequence_to_Go

func ParameterEvent__Sequence_to_Go(goSlice *[]ParameterEvent, cSlice CParameterEvent__Sequence)

func ParameterType__Array_to_C

func ParameterType__Array_to_C(cSlice []CParameterType, goSlice []ParameterType)

func ParameterType__Array_to_Go

func ParameterType__Array_to_Go(goSlice []ParameterType, cSlice []CParameterType)

func ParameterType__Sequence_to_C

func ParameterType__Sequence_to_C(cSlice *CParameterType__Sequence, goSlice []ParameterType)

func ParameterType__Sequence_to_Go

func ParameterType__Sequence_to_Go(goSlice *[]ParameterType, cSlice CParameterType__Sequence)

func ParameterValue__Array_to_C

func ParameterValue__Array_to_C(cSlice []CParameterValue, goSlice []ParameterValue)

func ParameterValue__Array_to_Go

func ParameterValue__Array_to_Go(goSlice []ParameterValue, cSlice []CParameterValue)

func ParameterValue__Sequence_to_C

func ParameterValue__Sequence_to_C(cSlice *CParameterValue__Sequence, goSlice []ParameterValue)

func ParameterValue__Sequence_to_Go

func ParameterValue__Sequence_to_Go(goSlice *[]ParameterValue, cSlice CParameterValue__Sequence)

func Parameter__Array_to_C

func Parameter__Array_to_C(cSlice []CParameter, goSlice []Parameter)

func Parameter__Array_to_Go

func Parameter__Array_to_Go(goSlice []Parameter, cSlice []CParameter)

func Parameter__Sequence_to_C

func Parameter__Sequence_to_C(cSlice *CParameter__Sequence, goSlice []Parameter)

func Parameter__Sequence_to_Go

func Parameter__Sequence_to_Go(goSlice *[]Parameter, cSlice CParameter__Sequence)

func SetParametersResult__Array_to_C

func SetParametersResult__Array_to_C(cSlice []CSetParametersResult, goSlice []SetParametersResult)

func SetParametersResult__Array_to_Go

func SetParametersResult__Array_to_Go(goSlice []SetParametersResult, cSlice []CSetParametersResult)

func SetParametersResult__Sequence_to_C

func SetParametersResult__Sequence_to_C(cSlice *CSetParametersResult__Sequence, goSlice []SetParametersResult)

func SetParametersResult__Sequence_to_Go

func SetParametersResult__Sequence_to_Go(goSlice *[]SetParametersResult, cSlice CSetParametersResult__Sequence)

Types

type CLog

type FloatingPointRange

type FloatingPointRange struct {
	FromValue float64 `yaml:"from_value"` // Start value for valid values, inclusive.
	ToValue   float64 `yaml:"to_value"`   // End value for valid values, inclusive.
	Step      float64 `yaml:"step"`       // Size of valid steps between the from and to bound.Step is considered to be a magnitude, therefore negative values are treatedthe same as positive values, and a step value of zero implies a continuousrange of values.Ideally, the step would be less than or equal to the distance between thebounds, as well as an even multiple of the distance between the bounds, butneither are required.If the absolute value of the step is larger than or equal to the distancebetween the two bounds, then the bounds will be the only valid values. e.g. ifthe range is defined as {from_value: 1.0, to_value: 2.0, step: 5.0} then thevalid values will be 1.0 and 2.0.If the step is less than the distance between the bounds, but the distance isnot a multiple of the step, then the "to" bound will always be a valid value,e.g. if the range is defined as {from_value: 2.0, to_value: 5.0, step: 2.0}then the valid values will be 2.0, 4.0, and 5.0.
}

Do not create instances of this type directly. Always use NewFloatingPointRange function instead.

func NewFloatingPointRange

func NewFloatingPointRange() *FloatingPointRange

NewFloatingPointRange creates a new FloatingPointRange with default values.

func (*FloatingPointRange) Clone

func (*FloatingPointRange) CloneMsg

func (t *FloatingPointRange) CloneMsg() types.Message

func (*FloatingPointRange) SetDefaults

func (t *FloatingPointRange) SetDefaults()

type IntegerRange

type IntegerRange struct {
	FromValue int64  `yaml:"from_value"` // Start value for valid values, inclusive.
	ToValue   int64  `yaml:"to_value"`   // End value for valid values, inclusive.
	Step      uint64 `yaml:"step"`       // Size of valid steps between the from and to bound.A step value of zero implies a continuous range of values. Ideally, the stepwould be less than or equal to the distance between the bounds, as well as aneven multiple of the distance between the bounds, but neither are required.If the absolute value of the step is larger than or equal to the distancebetween the two bounds, then the bounds will be the only valid values. e.g. ifthe range is defined as {from_value: 1, to_value: 2, step: 5} then the validvalues will be 1 and 2.If the step is less than the distance between the bounds, but the distance isnot a multiple of the step, then the "to" bound will always be a valid value,e.g. if the range is defined as {from_value: 2, to_value: 5, step: 2} thenthe valid values will be 2, 4, and 5.
}

Do not create instances of this type directly. Always use NewIntegerRange function instead.

func NewIntegerRange

func NewIntegerRange() *IntegerRange

NewIntegerRange creates a new IntegerRange with default values.

func (*IntegerRange) Clone

func (t *IntegerRange) Clone() *IntegerRange

func (*IntegerRange) CloneMsg

func (t *IntegerRange) CloneMsg() types.Message

func (*IntegerRange) SetDefaults

func (t *IntegerRange) SetDefaults()

type ListParametersResult

type ListParametersResult struct {
	Names    []string `yaml:"names"`    // The resulting parameters under the given prefixes.
	Prefixes []string `yaml:"prefixes"` // The resulting prefixes under the given prefixes.TODO(wjwwood): link to prefix definition and rules.
}

Do not create instances of this type directly. Always use NewListParametersResult function instead.

func NewListParametersResult

func NewListParametersResult() *ListParametersResult

NewListParametersResult creates a new ListParametersResult with default values.

func (*ListParametersResult) Clone

func (*ListParametersResult) CloneMsg

func (t *ListParametersResult) CloneMsg() types.Message

func (*ListParametersResult) SetDefaults

func (t *ListParametersResult) SetDefaults()

type Log

type Log struct {
	Stamp    builtin_interfaces_msg.Time `yaml:"stamp"`    // Timestamp when this message was generated by the node.
	Level    uint8                       `yaml:"level"`    // Corresponding log level, see above definitions.
	Name     string                      `yaml:"name"`     // The name representing the logger this message came from.
	Msg      string                      `yaml:"msg"`      // The full log message.
	File     string                      `yaml:"file"`     // The file the message came from.
	Function string                      `yaml:"function"` // The function the message came from.
	Line     uint32                      `yaml:"line"`     // The line in the file the message came from.
}

Do not create instances of this type directly. Always use NewLog function instead.

func NewLog

func NewLog() *Log

NewLog creates a new Log with default values.

func (*Log) Clone

func (t *Log) Clone() *Log

func (*Log) CloneMsg

func (t *Log) CloneMsg() types.Message

func (*Log) SetDefaults

func (t *Log) SetDefaults()

type Parameter

type Parameter struct {
	Name  string         `yaml:"name"`  // The full name of the parameter.
	Value ParameterValue `yaml:"value"` // The parameter's value which can be one of several types, see`ParameterValue.msg` and `ParameterType.msg`.
}

Do not create instances of this type directly. Always use NewParameter function instead.

func NewParameter

func NewParameter() *Parameter

NewParameter creates a new Parameter with default values.

func (*Parameter) Clone

func (t *Parameter) Clone() *Parameter

func (*Parameter) CloneMsg

func (t *Parameter) CloneMsg() types.Message

func (*Parameter) SetDefaults

func (t *Parameter) SetDefaults()

type ParameterDescriptor

type ParameterDescriptor struct {
	Name                  string               `yaml:"name"`                   // The name of the parameter.
	Type                  uint8                `yaml:"type"`                   // Enum values are defined in the `ParameterType.msg` message.
	Description           string               `yaml:"description"`            // Description of the parameter, visible from introspection tools.
	AdditionalConstraints string               `yaml:"additional_constraints"` // Plain English description of additional constraints which cannot be expressedwith the available constraints, e.g. "only prime numbers".By convention, this should only be used to clarify constraints which cannotbe completely expressed with the parameter constraints below.
	ReadOnly              bool                 `yaml:"read_only"`              // If 'true' then the value cannot change after it has been initialized.
	FloatingPointRange    []FloatingPointRange `yaml:"floating_point_range"`   // FloatingPointRange consists of a from_value, a to_value, and a step.
	IntegerRange          []IntegerRange       `yaml:"integer_range"`          // IntegerRange consists of a from_value, a to_value, and a step.
}

Do not create instances of this type directly. Always use NewParameterDescriptor function instead.

func NewParameterDescriptor

func NewParameterDescriptor() *ParameterDescriptor

NewParameterDescriptor creates a new ParameterDescriptor with default values.

func (*ParameterDescriptor) Clone

func (*ParameterDescriptor) CloneMsg

func (t *ParameterDescriptor) CloneMsg() types.Message

func (*ParameterDescriptor) SetDefaults

func (t *ParameterDescriptor) SetDefaults()

type ParameterEvent

type ParameterEvent struct {
	Stamp             builtin_interfaces_msg.Time `yaml:"stamp"`              // The time stamp when this parameter event occurred.
	Node              string                      `yaml:"node"`               // Fully qualified ROS path to node.
	NewParameters     []Parameter                 `yaml:"new_parameters"`     // New parameters that have been set for this node.
	ChangedParameters []Parameter                 `yaml:"changed_parameters"` // Parameters that have been changed during this event.
	DeletedParameters []Parameter                 `yaml:"deleted_parameters"` // Parameters that have been deleted during this event.
}

Do not create instances of this type directly. Always use NewParameterEvent function instead.

func NewParameterEvent

func NewParameterEvent() *ParameterEvent

NewParameterEvent creates a new ParameterEvent with default values.

func (*ParameterEvent) Clone

func (t *ParameterEvent) Clone() *ParameterEvent

func (*ParameterEvent) CloneMsg

func (t *ParameterEvent) CloneMsg() types.Message

func (*ParameterEvent) SetDefaults

func (t *ParameterEvent) SetDefaults()

type ParameterEventDescriptors

type ParameterEventDescriptors struct {
	NewParameters     []ParameterDescriptor `yaml:"new_parameters"`
	ChangedParameters []ParameterDescriptor `yaml:"changed_parameters"`
	DeletedParameters []ParameterDescriptor `yaml:"deleted_parameters"`
}

Do not create instances of this type directly. Always use NewParameterEventDescriptors function instead.

func NewParameterEventDescriptors

func NewParameterEventDescriptors() *ParameterEventDescriptors

NewParameterEventDescriptors creates a new ParameterEventDescriptors with default values.

func (*ParameterEventDescriptors) Clone

func (*ParameterEventDescriptors) CloneMsg

func (t *ParameterEventDescriptors) CloneMsg() types.Message

func (*ParameterEventDescriptors) SetDefaults

func (t *ParameterEventDescriptors) SetDefaults()

type ParameterType

type ParameterType struct {
}

Do not create instances of this type directly. Always use NewParameterType function instead.

func NewParameterType

func NewParameterType() *ParameterType

NewParameterType creates a new ParameterType with default values.

func (*ParameterType) Clone

func (t *ParameterType) Clone() *ParameterType

func (*ParameterType) CloneMsg

func (t *ParameterType) CloneMsg() types.Message

func (*ParameterType) SetDefaults

func (t *ParameterType) SetDefaults()

type ParameterValue

type ParameterValue struct {
	Type              uint8     `yaml:"type"`                // The type of this parameter, which corresponds to the appropriate field below.
	BoolValue         bool      `yaml:"bool_value"`          // Boolean value, can be either true or false.
	IntegerValue      int64     `yaml:"integer_value"`       // Integer value ranging from -9,223,372,036,854,775,808 to9,223,372,036,854,775,807.
	DoubleValue       float64   `yaml:"double_value"`        // A double precision floating point value following IEEE 754.
	StringValue       string    `yaml:"string_value"`        // A textual value with no practical length limit.
	ByteArrayValue    []byte    `yaml:"byte_array_value"`    // An array of bytes, used for non-textual information.
	BoolArrayValue    []bool    `yaml:"bool_array_value"`    // An array of boolean values.
	IntegerArrayValue []int64   `yaml:"integer_array_value"` // An array of 64-bit integer values.
	DoubleArrayValue  []float64 `yaml:"double_array_value"`  // An array of 64-bit floating point values.
	StringArrayValue  []string  `yaml:"string_array_value"`  // An array of string values.
}

Do not create instances of this type directly. Always use NewParameterValue function instead.

func NewParameterValue

func NewParameterValue() *ParameterValue

NewParameterValue creates a new ParameterValue with default values.

func (*ParameterValue) Clone

func (t *ParameterValue) Clone() *ParameterValue

func (*ParameterValue) CloneMsg

func (t *ParameterValue) CloneMsg() types.Message

func (*ParameterValue) SetDefaults

func (t *ParameterValue) SetDefaults()

type SetParametersResult

type SetParametersResult struct {
	Successful bool   `yaml:"successful"` // A true value of the same index indicates that the parameter was setsuccessfully. A false value indicates the change was rejected.
	Reason     string `yaml:"reason"`     // Reason why the setting was either successful or a failure. This should only beused for logging and user interfaces.
}

Do not create instances of this type directly. Always use NewSetParametersResult function instead.

func NewSetParametersResult

func NewSetParametersResult() *SetParametersResult

NewSetParametersResult creates a new SetParametersResult with default values.

func (*SetParametersResult) Clone

func (*SetParametersResult) CloneMsg

func (t *SetParametersResult) CloneMsg() types.Message

func (*SetParametersResult) SetDefaults

func (t *SetParametersResult) SetDefaults()

Jump to

Keyboard shortcuts

? : This menu
/ : Search site
f or F : Jump to
y or Y : Canonical URL