ros

package
v0.0.0-...-d9e4dd4 Latest Latest
Warning

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

Go to latest
Published: Feb 8, 2020 License: Apache-2.0 Imports: 22 Imported by: 0

Documentation

Index

Constants

View Source
const (
	// Sep defines the sequential seperater identifier.
	Sep = "/"

	// GlobalNS defines the global namespace identifier.
	GlobalNS = "/"

	// PrivateNS defines the private namespace identifier.
	PrivateNS = "~"
)

Variables

This section is empty.

Functions

This section is empty.

Types

type DefaultLogger

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

DefaultLogger is the default logger that rosgo uses to log various logging entries. DefaultLogger implements the logger interface that rosgo defines.

func NewDefaultLogger

func NewDefaultLogger() *DefaultLogger

NewDefaultLogger creates and returns a new rosgo logger instance

func (*DefaultLogger) Debug

func (logger *DefaultLogger) Debug(v ...interface{})

Debug logs entry/entries v when the logger level is set to DebugLevel or less

func (*DefaultLogger) Debugf

func (logger *DefaultLogger) Debugf(format string, v ...interface{})

Debugf formats and logs entry/entries v when the logger level is set to DebugLevel or less

func (*DefaultLogger) Error

func (logger *DefaultLogger) Error(v ...interface{})

Error logs entry/entries v when the logger level is set to ErrorLevel or less

func (*DefaultLogger) Errorf

func (logger *DefaultLogger) Errorf(format string, v ...interface{})

Errorf formats and logs entry/entries v when the logger level is set to ErrorLevel or less

func (*DefaultLogger) Fatal

func (logger *DefaultLogger) Fatal(v ...interface{})

Fatal logs entry/entries v and exits the program when the logger level is set to FatalLevel or less

func (*DefaultLogger) Fatalf

func (logger *DefaultLogger) Fatalf(format string, v ...interface{})

Fatalf formats and logs entry/entries v and exits the program when the logger level is set to FatalLevel or less

func (*DefaultLogger) Info

func (logger *DefaultLogger) Info(v ...interface{})

Info logs entry/entries v when the logger level is set to InfoLevel or less

func (*DefaultLogger) Infof

func (logger *DefaultLogger) Infof(format string, v ...interface{})

Infof formats and logs entry/entries v when the logger level is set to InfoLevel or less

func (*DefaultLogger) SetSeverity

func (logger *DefaultLogger) SetSeverity(severity LogLevel)

SetSeverity sets the logging level of DefaultLogger

func (*DefaultLogger) Severity

func (logger *DefaultLogger) Severity() LogLevel

Severity returns the logging level of DefaultLogger

func (*DefaultLogger) Warn

func (logger *DefaultLogger) Warn(v ...interface{})

Warn logs entry/entries v when the logger level is set to WarnLevel or less

func (*DefaultLogger) Warnf

func (logger *DefaultLogger) Warnf(format string, v ...interface{})

Warnf formats and logs entry/entries v when the logger level is set to WarnLevel or less

type Duration

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

Duration is ros duration primitive that defines a period of time.

func NewDuration

func NewDuration(sec uint32, nsec uint32) Duration

NewDuration creates a new instance of ros duration from seconds and nanoseconds.

func (*Duration) Add

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

Add adds and returns duration (d+other).

func (*Duration) Cmp

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

Cmp compares duration d with duration other. Return integer representing the comparison.

1 - d > other
0 - d == other

-1 - d < other

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 sleeps for period of time specified in d.

func (*Duration) Sub

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

Sub subtracts and returns duration (d-other).

func (*Duration) ToNSec

func (t *Duration) ToNSec() uint64

func (*Duration) ToSec

func (t *Duration) ToSec() float64

type LogLevel

type LogLevel int

LogLevel defines the logging level of default rosgo logger.

const (
	//LogLevelDebug is for logging debugging entries that are very verbose.
	LogLevelDebug LogLevel = iota
	// LogLevelInfo is for logging information entries that gives an idea of what's going on in the application.
	LogLevelInfo
	// LogLevelWarn is for logging non-critical entries that needs to be taken a look at.
	LogLevelWarn
	// LogLevelError is for logging error entries that represent something failing in the application.
	LogLevelError
	// LogLevelFatal is for logging unrecoverable failures and exiting (non-zero) the application.
	LogLevelFatal
)

type Logger

type Logger interface {
	Severity() LogLevel
	SetSeverity(severity LogLevel)
	Debug(v ...interface{})
	Debugf(format string, v ...interface{})
	Info(v ...interface{})
	Infof(format string, v ...interface{})
	Warn(v ...interface{})
	Warnf(format string, v ...interface{})
	Error(v ...interface{})
	Errorf(format string, v ...interface{})
	Fatal(v ...interface{})
	Fatalf(format string, v ...interface{})
}

Logger defines an interface that a ros logger should implement

type Message

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

Message defines the interface that a ros message should implement

type MessageEvent

type MessageEvent struct {
	// PublisherName is the name of message publisher.
	PublisherName string

	// ReceiptTime is the timestamp of when the message was received.
	ReceiptTime time.Time

	// ConnectionHeader is the HTTP connection header of the connection between
	// the subscriber node and the publisher node.
	ConnectionHeader map[string]string
}

MessageEvent defines the event information struct that contains meta information for each ros message received from a publisher.

type MessageType

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

MessageType defines the interface that a ros message type should implement

type NameMap

type NameMap map[string]string

NameMap defines a string key/value map that is used to store argument/namespace mappings

type Node

type Node interface {
	// NewPublisher creates a publisher which can used to publish ros messages of type MessageType
	// to the specified topic.
	NewPublisher(topic string, msgType MessageType) Publisher

	// NewPublisherWithCallbacks creates 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

	// NewSubscriber creates a subscriber to a topic and calls callback on receiving a message.
	// Callback should be a function which takes 0, 1, or 2 arguments.
	//
	// 0-arguments - Callback will simply be called without the message.
	// 1-arguments - Callback argument should be of the generated message type.
	// 2-arguments - Callback 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

	// NewServiceClient creates a service client which can be used to connect to a service server
	// send service requests.
	NewServiceClient(service string, srvType ServiceType) ServiceClient

	// NewServiceServer creates a service server that advertises the server and responds to the
	// service requests from service clients.
	NewServiceServer(service string, srvType ServiceType, callback interface{}) ServiceServer

	// OK represents the status of ros node.
	OK() bool

	// SpinOnce executes the job at the top of the Job queue.
	// Job queue consists of callback functions for subscribers and service server.
	// Blocking callbacks or callbacks that take too long to execute will result in new messages
	// being dropped due to job queue being full.
	SpinOnce()

	// Spin is job executor that continuosly starts executing callback jobs in the job queue.
	// Spin is a blocking call that unblocks only on node shutdown.
	Spin()

	// Shutdown stops the ros node
	Shutdown()

	// GetParam gets parameter value from the parameter server it it exists.
	// Non nil error will be returned if the parameter doesn't exists or the node
	// is unable to send the get param request to the paramter server.
	GetParam(name string) (interface{}, error)

	// SetParam sets parameter value on the parameter server which can be
	// retrieved or updated using parameter server API.
	// Returns a non nil error when unable to set the param on the server.
	SetParam(name string, value interface{}) error

	// HasParam checks if the parameter exists on the parameter server.
	// Return a non nil error when the node is unable to connect to paramter server.
	HasParam(name string) (bool, error)

	// SearchParam searches for the param in caller's namespace and proceeds upwards
	// through parent namespaces until Parameter Server finds a matching key.
	// More about parameter server API: https://wiki.ros.org/ROS/Parameter%20Server%20API
	SearchParam(name string) (string, error)

	// DeleteParam deletes the parameter from the parameter server.
	DeleteParam(name string) error

	// Logger returns the logger being used by the ros node.
	Logger() Logger

	// SetLogger changes the default logger used by ros node to the one specified in the call.
	// Custom loggers that implement the Logger interface can be set as the default logger.
	SetLogger(Logger)

	// NonRosArgs returns an array of all the non ros arguments of the ros node.
	NonRosArgs() []string
	Name() string
}

Node defines the interface that a ros node should implement

func NewNode

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

NewNode creates and returns a new instance of ros node Returns a non nil error when unable connect to ros master or create a new node.

type Publisher

type Publisher interface {
	// Publish publishes ros message
	Publish(msg Message)

	// GetNumSubscribers gets the number of subscribers to the publishing topic
	GetNumSubscribers() int

	// Shutdown stops the publisher
	Shutdown()
}

Publisher can be used to publish a ros messages to a specific topic. Shutdown can be used to shutdown this particular publisher. All running subscribers, publishers and services are shutdown on node exit.

type Rate

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

Rate defines a struct that can be used to run loops at a desired frequency. Based on: http://docs.ros.org/diamondback/api/rostime/html/classros_1_1Rate.html

func CycleTime

func CycleTime(d Duration) Rate

CycleTime creates and returns rate based on cycle time specified in ros::duration.

func NewRate

func NewRate(frequency float64) Rate

NewRate creates and returns rate based on frequency specified in hertz.

func (*Rate) CycleTime

func (r *Rate) CycleTime() Duration

CycleTime returns the actual runtime of a cycle from start to sleep.

func (*Rate) ExpectedCycleTime

func (r *Rate) ExpectedCycleTime() Duration

ExpectedCycleTime returns the expected cycle timw which is one over the frequency passed while create rate.

func (*Rate) Reset

func (r *Rate) Reset()

Reset resets the start time of rate to now.

func (*Rate) Sleep

func (r *Rate) Sleep() error

Sleep sleeps for any leftover time in a cycle. Calculated from the last time sleep, reset, or the constructor was called.

type Service

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

Service defines the interface that the code created/autogenerated for any service definitions should implement

type ServiceClient

type ServiceClient interface {
	// Call calls a service server with a service request.
	Call(srv Service) error

	// Shutdown stops the service client.
	Shutdown()
}

ServiceClient can be used to call a service server with a service request. It can also be used to shutdown the client.

type ServiceServer

type ServiceServer interface {
	// Shutdown stops the service server.
	Shutdown()
}

ServiceServer can be used to shutdown a running service server

type ServiceType

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

ServiceType defines the interface that the code created/autogenerated for any service definitions should implement.

type SingleSubscriberPublisher

type SingleSubscriberPublisher interface {
	// Publish publishes ros message
	Publish(msg Message)

	// GetSubscriberName gets the name of the single subscriber
	GetSubscriberName() string

	// GetTopic gets the name of the topic that we are publishing to.
	GetTopic() string
}

SingleSubscriberPublisher is publisher which 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 gets the numbers of publishers to the topic we are subscribed to has.
	GetNumPublishers() int

	// Shutdown stop subscriber.
	Shutdown()
}

Subscriber can be used to get the number of publishers to topic or shutdown the subscriber. Messages are received using the callback passed during subscriber creation.

type Time

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

Time defines a struct that represents ros time.

func NewTime

func NewTime(sec uint32, nsec uint32) Time

NewTime creates and returns a new instance of ros time.

func Now

func Now() Time

Now returns the current ros time.

func (*Time) Add

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

Add adds d duration to time t.

func (*Time) Cmp

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

Cmp compares time t and time other. Return integer representing the comparison.

1 : t > other
0 : t == other

-1 : t < other

func (*Time) Diff

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

Diff returns the duration difference between time t and time from.

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 subtracts d duration from time t.

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