ros

package
v0.0.0-...-59726dd Latest Latest
Warning

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

Go to latest
Published: Jul 10, 2020 License: Apache-2.0 Imports: 29 Imported by: 0

Documentation

Index

Constants

View Source
const (
	//Sep is a namespace separator string
	Sep = "/"
	//GlobalNS is the global namespace initial separator string
	GlobalNS = "/"
	//PrivateNS is private namespace initial separator string
	PrivateNS = "~"
)
View Source
const (
	//APIStatusError is an API call which returned an Error
	APIStatusError = -1
	//APIStatusFailure is a failed API call
	APIStatusFailure = 0
	//APIStatusSuccess is a successful API call
	APIStatusSuccess = 1
	//Remap string constant for splitting components
	Remap = ":="
)

Variables

This section is empty.

Functions

func DefaultLogger

func DefaultLogger() *logrus.Logger

DefaultLogger returns an instance of the default logger

func GetRuntimePackagePath

func GetRuntimePackagePath() string

GetRuntimePackagePath returns the ROS package search path which will be used by DynamicMessage to look up ROS message definitions at runtime. By default, this will be equivalent to the ${ROS_PACKAGE_PATH} environment variable.

func NewLogger

func NewLogger() *logrus.Logger

NewLogger returns a new instance of a logger

func PingMasterURI

func PingMasterURI(calleeURI string) bool

PingMasterURI is intended to return true if a dial to the ros master URI returns successfully

func ResetContext

func ResetContext()

ResetContext resets the package path context so that a new one will be generated

func SetRuntimePackagePath

func SetRuntimePackagePath(path string)

SetRuntimePackagePath sets the ROS package search path which will be used by DynamicMessage to look up ROS message definitions at runtime.

Types

type Duration

type Duration struct {
	// contains filtered or unexported fields
}

Duration type which is a wrapper for a temporal value of {sec,nsec}

func NewDuration

func NewDuration(sec uint32, nsec uint32) Duration

NewDuration instantiates a new Duration item with given sec and nsec integers

func (*Duration) Add

func (d *Duration) Add(other Duration) Duration

Add function for adding two durations together

func (*Duration) Cmp

func (d *Duration) Cmp(other Duration) int

Cmp function to compare two durations

func (*Duration) FromNSec

func (t *Duration) FromNSec(nsec uint64)

func (*Duration) FromSec

func (t *Duration) FromSec(sec float64)

func (*Duration) IsZero

func (t *Duration) IsZero() bool

func (*Duration) Normalize

func (t *Duration) Normalize()

func (*Duration) Sleep

func (d *Duration) Sleep() error

Sleep function pauses go routine for duration d

func (*Duration) Sub

func (d *Duration) Sub(other Duration) Duration

Sub function for subtracting a duration from another

func (*Duration) ToNSec

func (t *Duration) ToNSec() uint64

func (*Duration) ToSec

func (t *Duration) ToSec() float64

type DynamicMessage

type DynamicMessage struct {
	// contains filtered or unexported fields
}

DynamicMessage abstracts an instance of a ROS Message whose type is only known at runtime. The schema of the message is denoted by the referenced DynamicMessageType, while the actual payload of the Message is stored in a map[string]interface{} which maps the name of each field to its value. DynamicMessage implements the rosgo Message interface, allowing it to be used throughout rosgo in the same manner as message types generated at compiletime by gengo.

func (*DynamicMessage) Data

func (m *DynamicMessage) Data() map[string]interface{}

Data returns the data map field of the DynamicMessage

func (*DynamicMessage) Deserialize

func (m *DynamicMessage) Deserialize(buf *bytes.Reader) error

Deserialize parses a byte stream into a DynamicMessage, thus reconstructing the fields of a received ROS message; required for ros.Message.

func (*DynamicMessage) MarshalJSON

func (m *DynamicMessage) MarshalJSON() ([]byte, error)

MarshalJSON provides a custom implementation of JSON marshalling, so that when the DynamicMessage is recursively marshalled using the standard Go json.marshal() mechanism, the resulting JSON representation is a compact representation of just the important message payload (and not the message definition). It's important that this representation matches the schema generated by GenerateJSONSchema().

func (*DynamicMessage) Serialize

func (m *DynamicMessage) Serialize(buf *bytes.Buffer) error

Serialize converts a DynamicMessage into a TCPROS bytestream allowing it to be published to other nodes; required for ros.Message.

func (*DynamicMessage) String

func (m *DynamicMessage) String() string

func (*DynamicMessage) Type

func (m *DynamicMessage) Type() MessageType

Type returns the ROS type of a dynamic message; required for ros.Message.

func (*DynamicMessage) UnmarshalJSON

func (m *DynamicMessage) UnmarshalJSON(buf []byte) error

UnmarshalJSON provides a custom implementation of JSON unmarshalling. Using the dynamicMessage provided, Msgspec is used to determine the individual parsing of each JSON encoded payload item into the correct Go type. It is important each type is correct so that the message serializes correctly and is understood by the ROS system

type DynamicMessageType

type DynamicMessageType struct {
	// contains filtered or unexported fields
}

DynamicMessageType abstracts the schema of a ROS Message whose schema is only known at runtime. DynamicMessageTypes are created by looking up the relevant schema information from ROS Message definition files. DynamicMessageType implements the rosgo MessageType interface, allowing it to be used throughout rosgo in the same manner as message schemas generated at compiletime by gengo.

func NewDynamicMessageType

func NewDynamicMessageType(typeName string) (*DynamicMessageType, error)

NewDynamicMessageType generates a DynamicMessageType corresponding to the specified typeName from the available ROS message definitions; typeName should be a fully-qualified ROS message type name. The first time the function is run, a message 'context' is created by searching through the available ROS message definitions, then the ROS message to be used for the definition is looked up by name. On subsequent calls, the ROS message type is looked up directly from the existing context.

func (*DynamicMessageType) GenerateJSONSchema

func (t *DynamicMessageType) GenerateJSONSchema(prefix string, topic string) ([]byte, error)

GenerateJSONSchema generates a (primitive) JSON schema for the associated DynamicMessageType; however note that since we are mostly interested in making schema's for particular _topics_, the function takes a string prefix, and string topic name, which are used to id the resulting schema.

func (*DynamicMessageType) MD5Sum

func (t *DynamicMessageType) MD5Sum() string

MD5Sum returns the ROS compatible MD5 sum of the message type; required for ros.MessageType.

func (*DynamicMessageType) Name

func (t *DynamicMessageType) Name() string

Name returns the full ROS name of the message type; required for ros.MessageType.

func (*DynamicMessageType) NewMessage

func (t *DynamicMessageType) NewMessage() Message

NewMessage creates a new DynamicMessage instantiating the message type; required for ros.MessageType.

func (*DynamicMessageType) Text

func (t *DynamicMessageType) Text() string

Text returns the full ROS message specification for this message type; required for ros.MessageType.

type JsonFloat32

type JsonFloat32 struct {
	F float32
}

func (JsonFloat32) MarshalJSON

func (f JsonFloat32) MarshalJSON() ([]byte, error)

func (JsonFloat32) String

func (f JsonFloat32) String() string

type JsonFloat64

type JsonFloat64 struct {
	F float64
}

func (JsonFloat64) MarshalJSON

func (f JsonFloat64) MarshalJSON() ([]byte, error)

func (JsonFloat64) String

func (f JsonFloat64) String() string

type Message

type Message interface {
	Type() MessageType
	Serialize(buf *bytes.Buffer) error
	Deserialize(buf *bytes.Reader) error
}

Message struct which contains the message type, serialize and deserialize functions

type MessageEvent

type MessageEvent struct {
	PublisherName    string
	ReceiptTime      time.Time
	ConnectionHeader map[string]string
}

MessageEvent is an optional second argument to a Subscriber callback.

type MessageType

type MessageType interface {
	Text() string
	MD5Sum() string
	Name() string
	NewMessage() Message
}

MessageType struct which contains the interface functions for the important properties of a message Text, Name, and MD5 sum are data used to identify message types while NewMessage instantiates the message fields

type NameMap

type NameMap map[string]string

NameMap is a string to string map of node names and resolved names

type NameResolver

type NameResolver struct {
	// contains filtered or unexported fields
}

NameResolver struct definition for the NameResolver object. Node name is the raw name of the node in question namespace is the directory/qualifier of the node, by default "/" mapping and resolvedMapping are NameMap maps

type Node

type Node interface {
	NewPublisher(topic string, msgType MessageType) (Publisher, error)
	// Create a publisher which gives you callbacks when subscribers
	// connect and disconnect.  The callbacks are called in their own
	// goroutines, so they don't need to return immediately to let the
	// connection proceed.
	NewPublisherWithCallbacks(topic string,
		msgType MessageType,
		connectCallback, disconnectCallback func(SingleSubscriberPublisher)) (Publisher, error)
	// callback should be a function which takes 0, 1, or 2 arguments.
	// If it takes 0 arguments, it will simply be called without the
	// message.  1-argument functions are the normal case, and the
	// argument should be of the generated message type.  If the
	// function takes 2 arguments, the first argument should be of the
	// generated message type and the second argument should be of
	// type MessageEvent.
	NewSubscriber(topic string, msgType MessageType, callback interface{}) (Subscriber, error)
	NewServiceClient(service string, srvType ServiceType) ServiceClient
	NewServiceServer(service string, srvType ServiceType, callback interface{}) ServiceServer

	RemoveSubscriber(topic string)
	RemovePublisher(topic string)

	OK() bool
	SpinOnce() bool
	Spin()
	Shutdown()
	Name() string
	Namespace() string
	QualifiedName() string

	GetParam(name string) (interface{}, error)
	SetParam(name string, value interface{}) error
	HasParam(name string) (bool, error)
	SearchParam(name string) (string, error)
	DeleteParam(name string) error

	GetPublishedTopics(subgraph string) ([]interface{}, error)
	GetTopicTypes() []interface{}

	Logger() *modular.ModuleLogger

	NonRosArgs() []string
}

Node interface which contains functions of a ROS Node

func NewNode

func NewNode(name string, args []string) (Node, error)

NewNode instantiates a newDefaultNode with name and arguments

func NewNodeWithLogs

func NewNodeWithLogs(name string, logger *modular.ModuleLogger, args []string) (Node, error)

NewNodeWithLogs instantiates a newDefaultNode with a provided logger

type Publisher

type Publisher interface {
	Publish(msg Message)
	Shutdown()
}

Publisher is interface for publisher and shutdown function

type Rate

type Rate struct {
	// contains filtered or unexported fields
}

Rate interface is a struct of Durations actual and expected cycle time, and start Time

func CycleTime

func CycleTime(d Duration) Rate

CycleTime returns a new Rate object of expected cycle time of duration given

func NewRate

func NewRate(frequency float64) Rate

NewRate returns a new Rate object of given frequency

func (*Rate) CycleTime

func (r *Rate) CycleTime() Duration

CycleTime returns duration of the Cycle time of a Rate object

func (*Rate) ExpectedCycleTime

func (r *Rate) ExpectedCycleTime() Duration

ExpectedCycleTime returns duration of the Expected Cycle time of a Rate object

func (*Rate) Reset

func (r *Rate) Reset()

Reset sets actual Cycle time and start time of Rate to 0/now

func (*Rate) Sleep

func (r *Rate) Sleep() error

Sleep pauses go routine for time = expectedCycleTime - (Now - Rate start)

type Service

type Service interface {
	ReqMessage() Message
	ResMessage() Message
}

Service interface contains the Request and Response ROS messages

type ServiceClient

type ServiceClient interface {
	Call(srv Service) error
	Shutdown()
}

ServiceClient is the interface for a service client with service call function

type ServiceFactory

type ServiceFactory interface {
	Name() string
	MD5Sum() string
}

ServiceFactory is an interface for Name and MD5 sum of service

type ServiceHandler

type ServiceHandler interface{}

ServiceHandler is a service handling interface

type ServiceServer

type ServiceServer interface {
	Shutdown()
}

ServiceServer is the interface for a service server with shutdown

type ServiceType

type ServiceType interface {
	MD5Sum() string
	Name() string
	RequestType() MessageType
	ResponseType() MessageType
	NewService() Service
}

ServiceType is the interface definition of a ROS Service This contains MD5sum and Name of service and the request and response message types NewService iinstantiates a new Service object

type SingleSubscriberPublisher

type SingleSubscriberPublisher interface {
	Publish(msg Message)
	GetSubscriberName() string
	GetTopic() string
}

SingleSubscriberPublisher only sends to one specific subscriber. This is sent as an argument to the connect and disconnect callback functions passed to Node.NewPublisherWithCallbacks().

type Subscriber

type Subscriber interface {
	GetNumPublishers() int
	Shutdown()
}

Subscriber is interface for GetNumPublishers function used in callbacks

type Time

type Time struct {
	// contains filtered or unexported fields
}

Time struct contains a temporal value {sec,nsec}

func NewTime

func NewTime(sec uint32, nsec uint32) Time

NewTime creates a Time object of given integers {sec,nsec}

func Now

func Now() Time

Now creates a Time object of value Now

func (*Time) Add

func (t *Time) Add(d Duration) Time

Add returns sum of Time and Duration given

func (*Time) Cmp

func (t *Time) Cmp(other Time) int

Cmp returns int comparison of two Time objects

func (*Time) Diff

func (t *Time) Diff(from Time) Duration

Diff returns difference of two Time objects as a Duration

func (*Time) FromNSec

func (t *Time) FromNSec(nsec uint64)

func (*Time) FromSec

func (t *Time) FromSec(sec float64)

func (*Time) IsZero

func (t *Time) IsZero() bool

func (*Time) Normalize

func (t *Time) Normalize()

func (*Time) Sub

func (t *Time) Sub(d Duration) Time

Sub returns subtraction of Time and Duration given

func (*Time) ToNSec

func (t *Time) ToNSec() uint64

func (*Time) ToSec

func (t *Time) ToSec() float64

Jump to

Keyboard shortcuts

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