Documentation ¶
Overview ¶
Deliberate trial and error have been conducted in finding the best way of interfacing with rcl or rclc.
rclc was initially considered, but: Executor subscription callback doesn't include the subscription, only the ros2 message. Thus we cannot intelligently and dynamically dispatch the ros2 message to the correct subscription callback on the golang layer. rcl wait_set has much more granular way of defining how the received messages are handled and allows for a more Golang-way of handling dynamic callbacks.
This file is part of rclgo ¶
Copyright © 2021 Technology Innovation Institute, United Arab Emirates ¶
Licensed under the Apache License, Version 2.0 (the "License");
http://www.apache.org/licenses/LICENSE-2.0
Index ¶
- Constants
- func DefaultLoggingOutputHandler(location unsafe.Pointer, severity int, name unsafe.Pointer, timestamp int64, ...)
- func Deserialize(buf []byte, ts types.MessageTypeSupport) (msg types.Message, err error)
- func ExpandTopicName(inputTopicName, nodeName, nodeNamespace string, ...) (expanded string, err error)
- func Init(args *Args) (err error)
- func InitLogging(args *Args) error
- func InitWithOpts(args *Args, opts *ContextOptions) (err error)
- func LoadDynamicMessageTypeSupport(pkgName, msgName string) (types.MessageTypeSupport, error)
- func Serialize(msg types.Message) (buf []byte, err error)
- func SetLoggingOutputHandler(h LoggingOutputHandler)
- func Spin(ctx context.Context) error
- func Uninit() (err error)
- type Action
- type ActionClient
- func (c *ActionClient) CancelGoal(ctx context.Context, request types.Message) (types.Message, error)
- func (c *ActionClient) Close() error
- func (c *ActionClient) GetResult(ctx context.Context, goalID *types.GoalID) (types.Message, error)
- func (c *ActionClient) Node() *Node
- func (c *ActionClient) SendGoal(ctx context.Context, goal types.Message) (types.Message, *types.GoalID, error)
- func (c *ActionClient) SendGoalRequest(ctx context.Context, request types.Message) (types.Message, error)
- func (c *ActionClient) WatchFeedback(ctx context.Context, goalID *types.GoalID, handler FeedbackHandler) <-chan error
- func (c *ActionClient) WatchGoal(ctx context.Context, goal types.Message, onFeedback FeedbackHandler) (result types.Message, goalID *types.GoalID, retErr error)
- func (c *ActionClient) WatchStatus(ctx context.Context, goalID *types.GoalID, handler StatusHandler) <-chan error
- type ActionClientInvalid
- type ActionClientOptions
- type ActionClientTakeFailed
- type ActionGoalAccepted
- type ActionGoalEventInvalid
- type ActionGoalHandleInvalid
- type ActionGoalRejected
- type ActionNameInvalid
- type ActionServer
- type ActionServerInvalid
- type ActionServerOptions
- type ActionServerTakeFailed
- type AlreadyInit
- type AlreadyShutdown
- type Args
- type BadAlloc
- type Client
- type ClientInvalid
- type ClientOptions
- type ClientTakeFailed
- type Clock
- type ClockType
- type Context
- func (c *Context) Clock() *Clock
- func (c *Context) Close() error
- func (c *Context) NewClock(clockType ClockType) (clock *Clock, err error)
- func (c *Context) NewNode(node_name, namespace string) (node *Node, err error)
- func (c *Context) NewTimer(timeout time.Duration, timer_callback func(*Timer)) (timer *Timer, err error)
- func (c *Context) NewWaitSet() (ws *WaitSet, err error)
- func (c *Context) SetClock(newClock *Clock)
- func (c *Context) Spin(ctx context.Context) error
- type ContextOptions
- type DurabilityPolicy
- type EndpointType
- type Error
- type EventInvalid
- type EventTakeFailed
- type ExecuteGoalFunc
- type FeedbackHandler
- type FeedbackSender
- type GID
- type GoalHandle
- type GoalStatus
- type HistoryPolicy
- type InvalidArgument
- type InvalidLogLevelRule
- type InvalidParamRule
- type InvalidRemapRule
- type InvalidRosArgs
- type LifecycleStateNotRegistered
- type LifecycleStateRegistered
- type LivelinessPolicy
- type LogSeverity
- type Logger
- func (l *Logger) Child(name string) *Logger
- func (l *Logger) Debug(a ...interface{}) error
- func (l *Logger) Debugf(format string, a ...interface{}) error
- func (l *Logger) Debugln(a ...interface{}) error
- func (l *Logger) EffectiveLevel() (LogSeverity, error)
- func (l *Logger) Error(a ...interface{}) error
- func (l *Logger) Errorf(format string, a ...interface{}) error
- func (l *Logger) Errorln(a ...interface{}) error
- func (l *Logger) Fatal(a ...interface{}) error
- func (l *Logger) Fatalf(format string, a ...interface{}) error
- func (l *Logger) Fatalln(a ...interface{}) error
- func (l *Logger) Info(a ...interface{}) error
- func (l *Logger) Infof(format string, a ...interface{}) error
- func (l *Logger) Infoln(a ...interface{}) error
- func (l *Logger) IsEnabledFor(level LogSeverity) bool
- func (l *Logger) Level() (LogSeverity, error)
- func (l *Logger) Log(level LogSeverity, a ...interface{}) error
- func (l *Logger) Logf(level LogSeverity, format string, a ...interface{}) error
- func (l *Logger) Logln(level LogSeverity, a ...interface{}) error
- func (l *Logger) Name() string
- func (l *Logger) Parent() *Logger
- func (l *Logger) SetLevel(level LogSeverity) error
- func (l *Logger) Warn(a ...interface{}) error
- func (l *Logger) Warnf(format string, a ...interface{}) error
- func (l *Logger) Warnln(a ...interface{}) error
- type LoggingOutputHandler
- type MessageInfo
- type MismatchedRmwId
- type Node
- func (n *Node) Close() error
- func (n *Node) Context() *Context
- func (n *Node) FullyQualifiedName() string
- func (n *Node) GetActionClientNamesAndTypesByNode(node, namespace string) (map[string][]string, error)
- func (n *Node) GetActionServerNamesAndTypesByNode(node, namespace string) (map[string][]string, error)
- func (n *Node) GetClientNamesAndTypesByNode(node, namespace string) (map[string][]string, error)
- func (n *Node) GetNodeNames() (names, namespaces []string, err error)
- func (n *Node) GetPublisherNamesAndTypesByNode(demangle bool, node, namespace string) (map[string][]string, error)
- func (n *Node) GetPublishersInfoByTopic(topic string, mangle bool) ([]TopicEndpointInfo, error)
- func (n *Node) GetServiceNamesAndTypesByNode(node, namespace string) (map[string][]string, error)
- func (n *Node) GetSubscriberNamesAndTypesByNode(demangle bool, node, namespace string) (map[string][]string, error)
- func (n *Node) GetSubscriptionsInfoByTopic(topic string, mangle bool) ([]TopicEndpointInfo, error)
- func (n *Node) GetTopicNamesAndTypes(demangle bool) (map[string][]string, error)
- func (n *Node) Logger() *Logger
- func (n *Node) Name() string
- func (n *Node) Namespace() string
- func (n *Node) NewActionClient(name string, ts types.ActionTypeSupport, opts *ActionClientOptions) (*ActionClient, error)
- func (n *Node) NewActionServer(name string, action Action, opts *ActionServerOptions) (*ActionServer, error)
- func (n *Node) NewClient(serviceName string, typeSupport types.ServiceTypeSupport, ...) (c *Client, err error)
- func (n *Node) NewPublisher(topicName string, ros2msg types.MessageTypeSupport, options *PublisherOptions) (pub *Publisher, err error)
- func (n *Node) NewService(name string, typeSupport types.ServiceTypeSupport, options *ServiceOptions, ...) (s *Service, err error)
- func (n *Node) NewSubscription(topicName string, ros2msg types.MessageTypeSupport, ...) (sub *Subscription, err error)
- func (n *Node) Spin(ctx context.Context) error
- type NodeInvalid
- type NodeInvalidName
- type NodeInvalidNamespace
- type NodeNameNonExistent
- type NotInit
- type Ok
- type Publisher
- type PublisherInvalid
- type PublisherOptions
- type QosProfile
- type ReliabilityPolicy
- type RequestID
- type RmwBadAlloc
- type RmwError
- type RmwIncorrectRmwImplementation
- type RmwInvalidArgument
- type RmwNodeNameNonExistent
- type RmwOk
- type RmwTimeout
- type RmwUnsupported
- type Service
- type ServiceInfo
- type ServiceInvalid
- type ServiceNameInvalid
- type ServiceOptions
- type ServiceRequestHandler
- type ServiceResponseSender
- type ServiceTakeFailed
- type StatusHandler
- type Subscription
- type SubscriptionCallback
- type SubscriptionInvalid
- type SubscriptionOptions
- type SubscriptionTakeFailed
- type Timeout
- type Timer
- type TimerCanceled
- type TimerInvalid
- type TopicEndpointInfo
- type TopicNameInvalid
- type UnknownReturnCode
- type UnknownSubstitution
- type Unsupported
- type WaitSet
- func (w *WaitSet) AddActionClients(clients ...*ActionClient)
- func (w *WaitSet) AddActionServers(servers ...*ActionServer)
- func (w *WaitSet) AddClients(clients ...*Client)
- func (w *WaitSet) AddServices(services ...*Service)
- func (w *WaitSet) AddSubscriptions(subs ...*Subscription)
- func (w *WaitSet) AddTimers(timers ...*Timer)
- func (w *WaitSet) Close() (err error)
- func (w *WaitSet) Context() *Context
- func (w *WaitSet) Run(ctx context.Context) (err error)
- type WaitSetEmpty
- type WaitSetFull
- type WaitSetInvalid
- type WrongLexeme
Examples ¶
Constants ¶
const ( DurationInfinite = 9223372036*time.Second + 854775807*time.Nanosecond DurationUnspecified = time.Duration(0) )
const DeadlineDefault = DurationUnspecified
const DefaultDomainID = math.MaxUint
Setting this as the domain ID causes ROS to use the value of ROS_DOMAIN_ID environment variable as the actual domain ID or zero if ROS_DOMAIN_ID not defined.
const GIDSize = 24
const LifespanDefault = DurationUnspecified
const LivelinessLeaseDurationDefault = DurationUnspecified
Variables ¶
This section is empty.
Functions ¶
func DefaultLoggingOutputHandler ¶
func DefaultLoggingOutputHandler( location unsafe.Pointer, severity int, name unsafe.Pointer, timestamp int64, format unsafe.Pointer, args unsafe.Pointer, )
DefaultLoggingOutputHandler is the logging output handler used by default, which logs messages based on ROS parameters used to initialize the logging system.
func Deserialize ¶
Deserialize deserializes buf to a message whose type support is ts. The contents of buf must match ts.
func ExpandTopicName ¶
func ExpandTopicName( inputTopicName, nodeName, nodeNamespace string, substitutions map[string]string, ) (expanded string, err error)
ExpandTopicName returns inputTopicName expanded to a fully qualified topic name.
substitutions may be nil, which is treated the same as an empty substitution map.
func InitLogging ¶
InitLogging initializes the logging system, which is required for using logging functionality.
Logging configuration can be updated by calling InitLogging again with the desired args.
If the logging system has not yet been initialized on the first call of Init or NewContext, logging is initialized by that call using the passed arguments. Unlike InitLogging, Init and NewContext will not update logging configuration if logging has already been initialized.
func InitWithOpts ¶
func InitWithOpts(args *Args, opts *ContextOptions) (err error)
InitWithOpts initializes the global default context and logging system if they have not been initialized yet. Calling InitWithOpts multiple times after a successful (returning nil) call is a no-op.
A nil args is treated as an empty argument list.
If opts is nil, default options are used.
func LoadDynamicMessageTypeSupport ¶
func LoadDynamicMessageTypeSupport(pkgName, msgName string) (types.MessageTypeSupport, error)
LoadDynamicMessageTypeSupport loads a message type support implementation dynamically.
MessageTypeSupport instances returned by LoadDynamicMessageTypeSupport support use cases related to handling only serialized messages. Methods New, PrepareMemory, ReleaseMemory, AsCStruct and AsGoStruct will panic.
Backwards compatibility is not guaranteed for this API. Use it only if necessary.
func SetLoggingOutputHandler ¶
func SetLoggingOutputHandler(h LoggingOutputHandler)
SetLoggingOutputHandler sets the current logging output handler to h. If h == nil, DefaultLoggingOutputHandler is used.
Types ¶
type Action ¶
type Action interface { // ExecuteGoal executes a goal. // // The description of the goal is passed in the GoalHandle. // // First ExecuteGoal must decide whether to accept the goal or not. The goal // can be accepted by calling GoalHandle.Accept. GoalHandle.Accept should be // called as soon as the decision to accept the goal is made, before // starting to execute the goal. // // ExecuteGoal returns a pair of (result, error). If ExecuteGoal returns a // nil error, the goal is assumed to be executed successfully to completion. // In this case the result must be non-nil, and its type support must be // TypeSupport().Result(). If ExecuteGoal returns a non-nil error, the // result is ignored. If the error is returned before accepting the goal, // the goal is considered to have been rejected. If the error is returned // after accepting the goal, the goal is considered to have been aborted. // // The context is used to notify cancellation of the goal. If the context is // canceled, ExecuteGoal should stop all processing as soon as possible. In // this case the return values of ExecuteGoal are ignored. // // ExecuteGoal may be called multiple times in parallel by the ActionServer. // Each call will receive a different GoalHandle. ExecuteGoal(ctx context.Context, goal *GoalHandle) (types.Message, error) // TypeSupport returns the type support for the action. The same value // must be returned on every invocation. TypeSupport() types.ActionTypeSupport }
Action can execute goals.
func NewAction ¶
func NewAction( typeSupport types.ActionTypeSupport, executeGoal ExecuteGoalFunc, ) Action
NewAction returns an Action implementation that uses typeSupport and executes goals using executeGoal.
type ActionClient ¶
type ActionClient struct {
// contains filtered or unexported fields
}
ActionClient communicates with an ActionServer to initiate and monitor the progress of goals.
All methods except Close are safe for concurrent use.
Example ¶
package main import ( "context" "fmt" example_interfaces_action "github.com/tiiuae/rclgo/internal/msgs/example_interfaces/action" "github.com/tiiuae/rclgo/pkg/rclgo" "github.com/tiiuae/rclgo/pkg/rclgo/types" ) func main() { err := rclgo.Init(nil) if err != nil { // handle error } defer rclgo.Uninit() node, err := rclgo.NewNode("my_node", "my_namespace") if err != nil { // handle error } client, err := node.NewActionClient( "fibonacci", example_interfaces_action.FibonacciTypeSupport, nil, ) if err != nil { // handle error } ctx := context.Background() goal := example_interfaces_action.NewFibonacci_Goal() goal.Order = 10 result, _, err := client.WatchGoal(ctx, goal, func(ctx context.Context, feedback types.Message) { fmt.Println("Got feedback:", feedback) }) if err != nil { // handle error } fmt.Println("Got result:", result) }
Output:
Example (Type_safe_wrapper) ¶
package main import ( "context" "fmt" example_interfaces_action "github.com/tiiuae/rclgo/internal/msgs/example_interfaces/action" "github.com/tiiuae/rclgo/pkg/rclgo" ) func main() { err := rclgo.Init(nil) if err != nil { // handle error } defer rclgo.Uninit() node, err := rclgo.NewNode("my_node", "my_namespace") if err != nil { // handle error } client, err := example_interfaces_action.NewFibonacciClient( node, "fibonacci", nil, ) if err != nil { // handle error } ctx := context.Background() goal := example_interfaces_action.NewFibonacci_Goal() goal.Order = 10 result, _, err := client.WatchGoal(ctx, goal, func(ctx context.Context, feedback *example_interfaces_action.Fibonacci_FeedbackMessage) { fmt.Println("Got feedback:", feedback) }) if err != nil { // handle error } fmt.Println("Got result:", result) }
Output:
func (*ActionClient) CancelGoal ¶
func (c *ActionClient) CancelGoal(ctx context.Context, request types.Message) (types.Message, error)
CancelGoal cancels goals.
A non-nil error is returned only if the processing of the request itself failed. CancelGoal returns normally even if the canceling fails. The status can be read from the returned response message.
The request includes a goal ID and a timestamp. If both the ID and the timestamp have zero values, all goals are canceled. If the ID is zero but the timestamp is not, all goals accepted at or before the timestamp are canceled. If the ID is not zero and the timestamp is zero, the goal with the specified ID is canceled. If both the ID and the timestamp are non-zero, the goal with the specified ID as well as all goals accepted at or before the timestamp are canceled.
The type of request is action_msgs/srv/CancelGoal_Request.
The type of the returned message is action_msgs/srv/CancelGoal_Response.
func (*ActionClient) Close ¶
func (c *ActionClient) Close() error
Close frees resources used by the ActionClient. A closed ActionClient must not be used.
func (*ActionClient) GetResult ¶
GetResult returns the result of the goal with goalID or an error if getting the result fails. If the goal has not yet reached a terminal state, GetResult waits for that to happen before returning.
The type support of the returned message is types.ActionTypeSupport.GetResult().Response().
func (*ActionClient) Node ¶
func (c *ActionClient) Node() *Node
Node returns the node c was created with.
func (*ActionClient) SendGoal ¶
func (c *ActionClient) SendGoal(ctx context.Context, goal types.Message) (types.Message, *types.GoalID, error)
SendGoal sends a new goal to the server and returns the status message of the goal. The ID for the goal is generated using a cryptographically secure random number generator.
A non-nil error is returned only if the processing of the request itself failed. SendGoal returns normally even if the goal is rejected, and the status can be read from the returned response message.
The type support of goal must be types.ActionTypeSupport.Goal().
The type support of the returned message is types.ActionTypeSupport.SendGoal().Response().
func (*ActionClient) SendGoalRequest ¶
func (c *ActionClient) SendGoalRequest(ctx context.Context, request types.Message) (types.Message, error)
SendGoalRequest sends a goal to the server and returns the status message of the goal.
The type support of request must be types.ActionTypeSupport.SendGoal().Request().
The type support of the returned message is types.ActionTypeSupport.SendGoal().Response().
A non-nil error is returned only if the processing of the request itself failed. SendGoalRequest returns normally even if the goal is rejected, and the status can be read from the returned response message.
func (*ActionClient) WatchFeedback ¶
func (c *ActionClient) WatchFeedback(ctx context.Context, goalID *types.GoalID, handler FeedbackHandler) <-chan error
WatchFeedback calls handler for every feedback message for the goal with id goalID. If goalID is nil, handler is called for all feedback messages regardless of which goal they belong to.
WatchFeedback returns after the handler has been registered. The returned channel will receive exactly one error value, which may be nil, and then the channel is closed. Reading the value from the channel is not required. Watching can be stopped by canceling ctx.
The type support of the message passed to handler is types.ActionTypeSupport.FeedbackMessage().
func (*ActionClient) WatchGoal ¶
func (c *ActionClient) WatchGoal(ctx context.Context, goal types.Message, onFeedback FeedbackHandler) (result types.Message, goalID *types.GoalID, retErr error)
WatchGoal combines functionality of SendGoal and WatchFeedback. It sends a goal to the server. If the goal is accepted, feedback for the goal is watched until the goal reaches a terminal state or ctx is canceled. If the goal is accepted and completes successfully, its result is returned. Otherwise a non-nil error is returned.
onFeedback may be nil, in which case feedback for the goal is not watched.
The type support of goal must be types.ActionTypeSupport.Goal().
The type support of the returned message is types.ActionTypeSupport.Result().
The type support of the message passed to onFeedback is types.ActionTypeSupport.FeedbackMessage().
func (*ActionClient) WatchStatus ¶
func (c *ActionClient) WatchStatus(ctx context.Context, goalID *types.GoalID, handler StatusHandler) <-chan error
WatchStatus calls handler for every status message regarding the goal with id goalID. If goalID is nil, handler is called for all status messages regardless of which goal they belong to.
WatchStatus returns after the handler has been registered. The returned channel will receive exactly one error value, which may be nil, and then the channel is closed. Reading the value from the channel is not required. Watching can be stopped by canceling ctx.
The type of the message passed to handler will be action_msgs/msg/GoalStatus.
type ActionClientInvalid ¶
type ActionClientInvalid struct {
// contains filtered or unexported fields
}
ActionClientInvalid Action client is invalid return code.
type ActionClientOptions ¶
type ActionClientOptions struct { GoalServiceQos QosProfile CancelServiceQos QosProfile ResultServiceQos QosProfile FeedbackTopicQos QosProfile StatusTopicQos QosProfile }
func NewDefaultActionClientOptions ¶
func NewDefaultActionClientOptions() *ActionClientOptions
type ActionClientTakeFailed ¶
type ActionClientTakeFailed struct {
// contains filtered or unexported fields
}
ActionClientTakeFailed Action client failed to take response return code.
type ActionGoalAccepted ¶
type ActionGoalAccepted struct {
// contains filtered or unexported fields
}
ActionGoalAccepted Action goal accepted return code.
type ActionGoalEventInvalid ¶
type ActionGoalEventInvalid struct {
// contains filtered or unexported fields
}
ActionGoalEventInvalid Action invalid event return code.
type ActionGoalHandleInvalid ¶
type ActionGoalHandleInvalid struct {
// contains filtered or unexported fields
}
ActionGoalHandleInvalid Action goal handle invalid return code.
type ActionGoalRejected ¶
type ActionGoalRejected struct {
// contains filtered or unexported fields
}
ActionGoalRejected Action goal rejected return code.
type ActionNameInvalid ¶
type ActionNameInvalid struct {
// contains filtered or unexported fields
}
ActionNameInvalid rcl action specific ret codes in 2XXXAction name does not pass validation return code.
type ActionServer ¶
type ActionServer struct {
// contains filtered or unexported fields
}
ActionServer listens for and executes goals sent by action clients.
Example ¶
//nolint:revive package main import ( "context" "errors" example_interfaces_action "github.com/tiiuae/rclgo/internal/msgs/example_interfaces/action" "github.com/tiiuae/rclgo/pkg/rclgo" "github.com/tiiuae/rclgo/pkg/rclgo/types" ) var fibonacci = rclgo.NewAction( example_interfaces_action.FibonacciTypeSupport, func(ctx context.Context, goal *rclgo.GoalHandle) (types.Message, error) { description := goal.Description.(*example_interfaces_action.Fibonacci_Goal) if description.Order < 0 { return nil, errors.New("order must be non-negative") } sender, err := goal.Accept() if err != nil { return nil, err } result := example_interfaces_action.NewFibonacci_Result() fb := example_interfaces_action.NewFibonacci_Feedback() var x, y, i int32 for y = 1; i < description.Order; x, y, i = y, x+y, i+1 { result.Sequence = append(result.Sequence, x) fb.Sequence = result.Sequence if err = sender.Send(fb); err != nil { goal.Logger().Error("failed to send feedback: ", err) } } return result, nil }, ) func main() { err := rclgo.Init(nil) if err != nil { // handle error } defer rclgo.Uninit() node, err := rclgo.NewNode("my_node", "my_namespace") if err != nil { // handle error } _, err = node.NewActionServer("fibonacci", fibonacci, nil) if err != nil { // handle error } ctx := context.Background() if err = rclgo.Spin(ctx); err != nil { // handle error } }
Output:
Example (Type_safe_wrapper) ¶
//nolint:revive package main import ( "context" "errors" example_interfaces_action "github.com/tiiuae/rclgo/internal/msgs/example_interfaces/action" "github.com/tiiuae/rclgo/pkg/rclgo" ) var typeSafeFibonacci = example_interfaces_action.NewFibonacciAction( func( ctx context.Context, goal *example_interfaces_action.FibonacciGoalHandle, ) (*example_interfaces_action.Fibonacci_Result, error) { if goal.Description.Order < 0 { return nil, errors.New("order must be non-negative") } sender, err := goal.Accept() if err != nil { return nil, err } result := example_interfaces_action.NewFibonacci_Result() fb := example_interfaces_action.NewFibonacci_Feedback() var x, y, i int32 for y = 1; i < goal.Description.Order; x, y, i = y, x+y, i+1 { result.Sequence = append(result.Sequence, x) fb.Sequence = result.Sequence if err = sender.Send(fb); err != nil { goal.Logger().Error("failed to send feedback: ", err) } } return result, nil }, ) func main() { err := rclgo.Init(nil) if err != nil { // handle error } defer rclgo.Uninit() node, err := rclgo.NewNode("my_node", "my_namespace") if err != nil { // handle error } _, err = example_interfaces_action.NewFibonacciServer(node, "fibonacci", typeSafeFibonacci, nil) if err != nil { // handle error } ctx := context.Background() if err = rclgo.Spin(ctx); err != nil { // handle error } }
Output:
func (*ActionServer) Close ¶
func (s *ActionServer) Close() (err error)
func (*ActionServer) Node ¶
func (s *ActionServer) Node() *Node
Node returns the node s was created with.
type ActionServerInvalid ¶
type ActionServerInvalid struct {
// contains filtered or unexported fields
}
ActionServerInvalid Action server is invalid return code.
type ActionServerOptions ¶
type ActionServerOptions struct { GoalServiceQos QosProfile CancelServiceQos QosProfile ResultServiceQos QosProfile FeedbackTopicQos QosProfile StatusTopicQos QosProfile ResultTimeout time.Duration Clock *Clock }
func NewDefaultActionServerOptions ¶
func NewDefaultActionServerOptions() *ActionServerOptions
type ActionServerTakeFailed ¶
type ActionServerTakeFailed struct {
// contains filtered or unexported fields
}
ActionServerTakeFailed Action server failed to take request return code.
type AlreadyInit ¶
type AlreadyInit struct {
// contains filtered or unexported fields
}
AlreadyInit rcl specific ret codes start at 100rcl_init() already called return code.
type AlreadyShutdown ¶
type AlreadyShutdown struct {
// contains filtered or unexported fields
}
AlreadyShutdown rcl_shutdown() already called return code.
type Args ¶
type Args struct {
// contains filtered or unexported fields
}
ROS2 is configured via CLI arguments, so merge them from different sources. See http://design.ros2.org/articles/ros_command_line_arguments.html for details.
func ParseArgs ¶
ParseArgs parses ROS 2 command line arguments from the given slice. Returns the parsed ROS 2 arguments and the remaining non-ROS arguments.
ParseArgs expects ROS 2 arguments to be wrapped between a pair of "--ros-args" and "--" arguments. See http://design.ros2.org/articles/ros_command_line_arguments.html for details.
Example ¶
package main import ( "fmt" "github.com/tiiuae/rclgo/pkg/rclgo" ) func main() { rosArgs, restArgs, err := rclgo.ParseArgs( []string{ "--extra0", "args0", "--ros-args", "--log-level", "DEBUG", "--", "--extra1", "args1", }, ) if err != nil { panic(err) } fmt.Printf("rosArgs: [%v]\n", rosArgs) fmt.Printf("restArgs: %+v\n\n", restArgs) rosArgs, restArgs, err = rclgo.ParseArgs( []string{"--ros-args", "--log-level", "INFO"}, ) if err != nil { panic(err) } fmt.Printf("rosArgs: [%v]\n", rosArgs) fmt.Printf("restArgs: %+v\n\n", restArgs) rosArgs, restArgs, err = rclgo.ParseArgs( []string{"--extra0", "args0", "--extra1", "args1"}, ) if err != nil { panic(err) } fmt.Printf("rosArgs: [%v]\n", rosArgs) fmt.Printf("restArgs: %+v\n\n", restArgs) rosArgs, restArgs, err = rclgo.ParseArgs(nil) if err != nil { panic(err) } fmt.Printf("rosArgs: [%v]\n", rosArgs) fmt.Printf("restArgs: %+v\n", restArgs) }
Output: rosArgs: [--log-level DEBUG] restArgs: [--extra0 args0 --extra1 args1] rosArgs: [--log-level INFO] restArgs: [] rosArgs: [] restArgs: [--extra0 args0 --extra1 args1] rosArgs: [] restArgs: []
type Client ¶
type Client struct {
// contains filtered or unexported fields
}
Client is used to send requests to and receive responses from a service.
Calling Send and Close is thread-safe. Creating clients is not thread-safe.
type ClientInvalid ¶
type ClientInvalid struct {
// contains filtered or unexported fields
}
ClientInvalid rcl service client specific ret codes in 5XXInvalid rcl_client_t given return code.
type ClientOptions ¶
type ClientOptions struct {
Qos QosProfile
}
func NewDefaultClientOptions ¶
func NewDefaultClientOptions() *ClientOptions
type ClientTakeFailed ¶
type ClientTakeFailed struct {
// contains filtered or unexported fields
}
ClientTakeFailed Failed to take a response from the client return code.
type Context ¶
type Context struct {
// contains filtered or unexported fields
}
Context manages resources for a set of RCL entities.
func DefaultContext ¶
func DefaultContext() *Context
DefaultContext returns the global default context or nil if Init has not yet been called.
func NewContext ¶
NewContext calls NewContextWithOpts with default options except for ClockType, which is set to the value passed to this function.
If clockType == 0, ClockTypeROSTime is used.
func NewContextWithOpts ¶
func NewContextWithOpts(rclArgs *Args, opts *ContextOptions) (ctx *Context, err error)
NewContextWithOpts initializes a new RCL context.
A nil rclArgs is treated as en empty argument list.
If logging has not yet been initialized, NewContextWithOpts will initialize it automatically using rclArgs for logging configuration.
If opts is nil, default options are used.
func (*Context) NewWaitSet ¶
type ContextOptions ¶
type ContextOptions struct { // The type of the default clock created for the Context. ClockType ClockType // The DDS domain ID of the Context. Should be in range [0, 101] or // DefaultDomainID. DomainID uint }
ContextOptions can be used to configure a Context.
func NewDefaultContextOptions ¶
func NewDefaultContextOptions() *ContextOptions
NewDefaultContextOptions returns the default options for a Context.
type DurabilityPolicy ¶
type DurabilityPolicy int
const ( DurabilitySystemDefault DurabilityPolicy = iota DurabilityTransientLocal DurabilityVolatile DurabilityUnknown )
type EndpointType ¶
type EndpointType int
const ( EndpointInvalid EndpointType = iota EndpointPublisher EndpointSubscription )
type EventInvalid ¶
type EventInvalid struct {
// contains filtered or unexported fields
}
EventInvalid rcl event specific ret codes in 20XXInvalid rcl_event_t given return code.
type EventTakeFailed ¶
type EventTakeFailed struct {
// contains filtered or unexported fields
}
EventTakeFailed Failed to take an event from the event handle
type ExecuteGoalFunc ¶
type FeedbackSender ¶
type FeedbackSender struct {
// contains filtered or unexported fields
}
FeedbackSender is used to send feedback about a goal.
type GoalHandle ¶
type GoalHandle struct { // The ID of the goal. Modifying this is undefined behavior. ID types.GoalID // Description is a message whose type support is // types.ActionTypeSupport.Goal(). Description types.Message // contains filtered or unexported fields }
GoalHandle is used to keep track of the status of a goal sent to an ActionServer.
func (*GoalHandle) Accept ¶
func (g *GoalHandle) Accept() (s *FeedbackSender, err error)
Accept accepts g and returns a FeedbackSender that can be used to send feedback about the goal to action clients. Calls after the first successful (returning a nil error) do not change the state of the goal and only return valid feedback senders. Accept should be called as soon as the goal is decided to be accepted. If Accept returns a non-nil error the returned FeedbackSender is nil and g is left in an unspecified but valid state. In that case it is usually appropriate to stop executing the goal and return the error returned by Accept.
func (*GoalHandle) Logger ¶
func (g *GoalHandle) Logger() *Logger
Logger is a shorthand for g.Server().Node().Logger().
func (*GoalHandle) Server ¶
func (g *GoalHandle) Server() *ActionServer
Server returns the ActionServer that is handling g.
type GoalStatus ¶
type GoalStatus int8
const ( GoalUnknown GoalStatus = iota // Unknown // Active states GoalAccepted // Accepted GoalExecuting // Executing GoalCanceling // Canceling // Terminal states GoalSucceeded // Succeeded GoalCanceled // Canceled GoalAborted // Aborted )
func (GoalStatus) String ¶
func (i GoalStatus) String() string
type HistoryPolicy ¶
type HistoryPolicy int
const ( HistorySystemDefault HistoryPolicy = iota HistoryKeepLast HistoryKeepAll HistoryUnknown )
type InvalidArgument ¶
type InvalidArgument = RmwInvalidArgument
InvalidArgument Invalid argument return code.
type InvalidLogLevelRule ¶
type InvalidLogLevelRule struct {
// contains filtered or unexported fields
}
InvalidLogLevelRule Argument is not a valid log level rule
type InvalidParamRule ¶
type InvalidParamRule struct {
// contains filtered or unexported fields
}
InvalidParamRule Argument is not a valid parameter rule
type InvalidRemapRule ¶
type InvalidRemapRule struct {
// contains filtered or unexported fields
}
InvalidRemapRule rcl argument parsing specific ret codes in 1XXXArgument is not a valid remap rule
type InvalidRosArgs ¶
type InvalidRosArgs struct {
// contains filtered or unexported fields
}
InvalidRosArgs Found invalid ros argument while parsing
type LifecycleStateNotRegistered ¶
type LifecycleStateNotRegistered struct {
// contains filtered or unexported fields
}
LifecycleStateNotRegistered rcl_lifecycle state not registered
type LifecycleStateRegistered ¶
type LifecycleStateRegistered struct {
// contains filtered or unexported fields
}
LifecycleStateRegistered rcl_lifecycle state register ret codes in 30XXrcl_lifecycle state registered
type LivelinessPolicy ¶
type LivelinessPolicy int
const ( LivelinessSystemDefault LivelinessPolicy = iota LivelinessAutomatic LivelinessManualByTopic LivelinessUnknown )
type LogSeverity ¶
type LogSeverity uint32
The severity levels of log messages / loggers.
const ( LogSeverityUnset LogSeverity = 0 ///< The unset log level LogSeverityDebug LogSeverity = 10 ///< The debug log level LogSeverityInfo LogSeverity = 20 ///< The info log level LogSeverityWarn LogSeverity = 30 ///< The warn log level LogSeverityError LogSeverity = 40 ///< The error log level LogSeverityFatal LogSeverity = 50 ///< The fatal log level )
func (LogSeverity) String ¶
func (s LogSeverity) String() string
type Logger ¶
type Logger struct {
// contains filtered or unexported fields
}
Logger can be used to log messages using the ROS 2 logging system.
Loggers are usable only after logging has been initialized. See InitLogging.
Logging methods prefixed with "Log" take the logging level as the first parameter. Methods prefixed with the name of a logging level are shorthands to "Log" methods, and log using the prefixed logging level.
Logging methods suffixed with "", "f" or "ln" format their arguments in the same way as fmt.Print, fmt.Printf and fmt.Println, respectively.
func GetLogger ¶
GetLogger returns the logger named name. If name is empty, the default logger is returned. Returns nil if name is invalid.
func (*Logger) Child ¶
Child returns the child logger of l named name. Returns nil if name is invalid.
func (*Logger) EffectiveLevel ¶
func (l *Logger) EffectiveLevel() (LogSeverity, error)
EffectiveLevel returns the effective logging level of l, which considers the logging levels of l's ancestors as well as the logging level of l itself. Note that this is not necessarily the same as Level.
func (*Logger) IsEnabledFor ¶
func (l *Logger) IsEnabledFor(level LogSeverity) bool
IsEnabledFor returns true if l can log messages whose severity is at least level and false if not.
func (*Logger) Level ¶
func (l *Logger) Level() (LogSeverity, error)
Level returns the logging level of l. Note that this is not necessarily the same as EffectiveLevel.
func (*Logger) Log ¶
func (l *Logger) Log(level LogSeverity, a ...interface{}) error
func (*Logger) Logf ¶
func (l *Logger) Logf(level LogSeverity, format string, a ...interface{}) error
func (*Logger) Logln ¶
func (l *Logger) Logln(level LogSeverity, a ...interface{}) error
func (*Logger) Parent ¶
Parent returns the parent logger of l. If l has no parent, the default logger is returned.
func (*Logger) SetLevel ¶
func (l *Logger) SetLevel(level LogSeverity) error
SetLevel sets the logging level of l.
type LoggingOutputHandler ¶
type LoggingOutputHandler = func( location unsafe.Pointer, severity int, name unsafe.Pointer, timestamp int64, format unsafe.Pointer, args unsafe.Pointer, )
LoggingOutputHandler is the function signature of logging output handling. Backwards compatibility is not guaranteed for this type alias. Use it only if necessary.
func GetLoggingOutputHandler ¶
func GetLoggingOutputHandler() LoggingOutputHandler
GetLoggingOutputHandler returns the current logging output handler.
type MessageInfo ¶
type MismatchedRmwId ¶
type MismatchedRmwId struct {
// contains filtered or unexported fields
}
MismatchedRmwId Mismatched rmw identifier return code.
type Node ¶
type Node struct {
// contains filtered or unexported fields
}
func (*Node) FullyQualifiedName ¶
FullyQualifiedName returns the fully qualified name of n, which includes the namespace as well as the name.
func (*Node) GetActionClientNamesAndTypesByNode ¶
func (*Node) GetActionServerNamesAndTypesByNode ¶
func (*Node) GetClientNamesAndTypesByNode ¶
func (*Node) GetNodeNames ¶
func (*Node) GetPublisherNamesAndTypesByNode ¶
func (*Node) GetPublishersInfoByTopic ¶
func (n *Node) GetPublishersInfoByTopic(topic string, mangle bool) ([]TopicEndpointInfo, error)
func (*Node) GetServiceNamesAndTypesByNode ¶
func (*Node) GetSubscriberNamesAndTypesByNode ¶
func (*Node) GetSubscriptionsInfoByTopic ¶
func (n *Node) GetSubscriptionsInfoByTopic(topic string, mangle bool) ([]TopicEndpointInfo, error)
func (*Node) GetTopicNamesAndTypes ¶
GetTopicNamesAndTypes returns a map of all known topic names to corresponding topic types. Note that multiple types may be associated with a single topic.
If demangle is true, topic names will be in the format used by the underlying middleware.
func (*Node) NewActionClient ¶
func (n *Node) NewActionClient( name string, ts types.ActionTypeSupport, opts *ActionClientOptions, ) (*ActionClient, error)
NewActionClient creates an action client that communicates with an action server.
func (*Node) NewActionServer ¶
func (n *Node) NewActionServer( name string, action Action, opts *ActionServerOptions, ) (*ActionServer, error)
NewActionServer creates a new action server.
opts must not be modified after passing it to this function. If opts is nil, default options are used.
func (*Node) NewClient ¶
func (n *Node) NewClient( serviceName string, typeSupport types.ServiceTypeSupport, options *ClientOptions, ) (c *Client, err error)
NewClient creates a new client.
options must not be modified after passing it to this function. If options is nil, default options are used.
func (*Node) NewPublisher ¶
func (n *Node) NewPublisher( topicName string, ros2msg types.MessageTypeSupport, options *PublisherOptions, ) (pub *Publisher, err error)
NewPublisher creates a new publisher.
options must not be modified after passing it to this function. If options is nil, default options are used.
func (*Node) NewService ¶
func (n *Node) NewService( name string, typeSupport types.ServiceTypeSupport, options *ServiceOptions, handler ServiceRequestHandler, ) (s *Service, err error)
NewService creates a new service.
options must not be modified after passing it to this function. If options is nil, default options are used.
func (*Node) NewSubscription ¶
func (n *Node) NewSubscription( topicName string, ros2msg types.MessageTypeSupport, options *SubscriptionOptions, subscriptionCallback SubscriptionCallback, ) (sub *Subscription, err error)
NewSubscription creates a new subscription.
options must not be modified after passing it to this function. If options is nil, default options are used.
type NodeInvalid ¶
type NodeInvalid struct {
// contains filtered or unexported fields
}
NodeInvalid rcl node specific ret codes in 2XXInvalid rcl_node_t given return code.
type NodeInvalidName ¶
type NodeInvalidName struct {
// contains filtered or unexported fields
}
NodeInvalidName Invalid node name return code.
type NodeInvalidNamespace ¶
type NodeInvalidNamespace struct {
// contains filtered or unexported fields
}
NodeInvalidNamespace Invalid node namespace return code.
type NodeNameNonExistent ¶
type NodeNameNonExistent struct {
// contains filtered or unexported fields
}
NodeNameNonExistent Failed to find node name
type NotInit ¶
type NotInit struct {
// contains filtered or unexported fields
}
NotInit rcl_init() not yet called return code.
type Publisher ¶
type Publisher struct { TopicName string // contains filtered or unexported fields }
func (*Publisher) GetSubscriptionCount ¶
GetSubscriptionCount returns the number of subscriptions matched to p.
func (*Publisher) PublishSerialized ¶
PublishSerialized publishes a message that has already been serialized.
type PublisherInvalid ¶
type PublisherInvalid struct {
// contains filtered or unexported fields
}
PublisherInvalid rcl publisher specific ret codes in 3XXInvalid rcl_publisher_t given return code.
type PublisherOptions ¶
type PublisherOptions struct {
Qos QosProfile
}
func NewDefaultPublisherOptions ¶
func NewDefaultPublisherOptions() *PublisherOptions
type QosProfile ¶
type QosProfile struct { History HistoryPolicy `yaml:"history"` Depth int `yaml:"depth"` Reliability ReliabilityPolicy `yaml:"reliability"` Durability DurabilityPolicy `yaml:"durability"` Deadline time.Duration `yaml:"deadline"` Lifespan time.Duration `yaml:"lifespan"` Liveliness LivelinessPolicy `yaml:"liveliness"` LivelinessLeaseDuration time.Duration `yaml:"liveliness_lease_duration"` AvoidRosNamespaceConventions bool `yaml:"avoid_ros_namespace_conventions"` }
func NewDefaultQosProfile ¶
func NewDefaultQosProfile() QosProfile
func NewDefaultServiceQosProfile ¶
func NewDefaultServiceQosProfile() QosProfile
func NewDefaultStatusQosProfile ¶
func NewDefaultStatusQosProfile() QosProfile
type ReliabilityPolicy ¶
type ReliabilityPolicy int
const ( ReliabilitySystemDefault ReliabilityPolicy = iota ReliabilityReliable ReliabilityBestEffort ReliabilityUnknown )
type RmwBadAlloc ¶
type RmwBadAlloc struct {
// contains filtered or unexported fields
}
RmwBadAlloc Failed to allocate memory
type RmwError ¶
type RmwError struct {
// contains filtered or unexported fields
}
RmwError Generic error to indicate operation could not complete successfully
type RmwIncorrectRmwImplementation ¶
type RmwIncorrectRmwImplementation struct {
// contains filtered or unexported fields
}
RmwIncorrectRmwImplementation Incorrect rmw implementation.
type RmwInvalidArgument ¶
type RmwInvalidArgument struct {
// contains filtered or unexported fields
}
RmwInvalidArgument Argument to function was invalid
type RmwNodeNameNonExistent ¶
type RmwNodeNameNonExistent struct {
// contains filtered or unexported fields
}
RmwNodeNameNonExistent rmw node specific ret codes in 2XXFailed to find node nameUsing same return code than in rcl
type RmwOk ¶
type RmwOk struct {
// contains filtered or unexported fields
}
RmwOk Return code for rmw functionsThe operation ran as expected
type RmwTimeout ¶
type RmwTimeout struct {
// contains filtered or unexported fields
}
RmwTimeout The operation was halted early because it exceeded its timeout critera
type RmwUnsupported ¶
type RmwUnsupported struct {
// contains filtered or unexported fields
}
RmwUnsupported The operation or event handling is not supported.
type ServiceInfo ¶
type ServiceInvalid ¶
type ServiceInvalid struct {
// contains filtered or unexported fields
}
ServiceInvalid rcl service server specific ret codes in 6XXInvalid rcl_service_t given return code.
type ServiceNameInvalid ¶
type ServiceNameInvalid struct {
// contains filtered or unexported fields
}
ServiceNameInvalid Service name (same as topic name) does not pass validation.
type ServiceOptions ¶
type ServiceOptions struct {
Qos QosProfile
}
func NewDefaultServiceOptions ¶
func NewDefaultServiceOptions() *ServiceOptions
type ServiceRequestHandler ¶
type ServiceRequestHandler func(*ServiceInfo, types.Message, ServiceResponseSender)
type ServiceResponseSender ¶
type ServiceTakeFailed ¶
type ServiceTakeFailed struct {
// contains filtered or unexported fields
}
ServiceTakeFailed Failed to take a request from the service return code.
type Subscription ¶
type Subscription struct { TopicName string Ros2MsgType types.MessageTypeSupport Callback SubscriptionCallback // contains filtered or unexported fields }
func (*Subscription) Close ¶
func (s *Subscription) Close() (err error)
Close frees the allocated memory
func (*Subscription) GetPublisherCount ¶
func (s *Subscription) GetPublisherCount() (int, error)
GetPublisherCount returns the number of publishers matched to s.
func (*Subscription) TakeMessage ¶
func (s *Subscription) TakeMessage(out types.Message) (*MessageInfo, error)
func (*Subscription) TakeSerializedMessage ¶
func (s *Subscription) TakeSerializedMessage() ([]byte, *MessageInfo, error)
TakeSerializedMessage takes a message without deserializing it and returns it as a byte slice.
type SubscriptionCallback ¶
type SubscriptionCallback func(*Subscription)
type SubscriptionInvalid ¶
type SubscriptionInvalid struct {
// contains filtered or unexported fields
}
SubscriptionInvalid rcl subscription specific ret codes in 4XXInvalid rcl_subscription_t given return code.
type SubscriptionOptions ¶
type SubscriptionOptions struct {
Qos QosProfile
}
func NewDefaultSubscriptionOptions ¶
func NewDefaultSubscriptionOptions() *SubscriptionOptions
type SubscriptionTakeFailed ¶
type SubscriptionTakeFailed struct {
// contains filtered or unexported fields
}
SubscriptionTakeFailed Failed to take a message from the subscription return code.
type Timer ¶
type Timer struct { Callback func(*Timer) // contains filtered or unexported fields }
func (*Timer) GetTimeUntilNextCall ¶
type TimerCanceled ¶
type TimerCanceled struct {
// contains filtered or unexported fields
}
TimerCanceled Given timer was canceled return code.
type TimerInvalid ¶
type TimerInvalid struct {
// contains filtered or unexported fields
}
TimerInvalid rcl timer specific ret codes in 8XXInvalid rcl_timer_t given return code.
type TopicEndpointInfo ¶
type TopicEndpointInfo struct { NodeName string NodeNamespace string TopicType string EndpointType EndpointType EndpointGID GID QosProfile QosProfile }
type TopicNameInvalid ¶
type TopicNameInvalid struct {
// contains filtered or unexported fields
}
TopicNameInvalid Topic name does not pass validation.
type UnknownReturnCode ¶
type UnknownReturnCode struct {
// contains filtered or unexported fields
}
type UnknownSubstitution ¶
type UnknownSubstitution struct {
// contains filtered or unexported fields
}
UnknownSubstitution Topic name substitution is unknown.
type WaitSet ¶
type WaitSet struct { Subscriptions []*Subscription Timers []*Timer Services []*Service Clients []*Client ActionClients []*ActionClient ActionServers []*ActionServer // contains filtered or unexported fields }
func NewWaitSet ¶
func (*WaitSet) AddActionClients ¶
func (w *WaitSet) AddActionClients(clients ...*ActionClient)
func (*WaitSet) AddActionServers ¶
func (w *WaitSet) AddActionServers(servers ...*ActionServer)
func (*WaitSet) AddClients ¶
func (*WaitSet) AddServices ¶
func (*WaitSet) AddSubscriptions ¶
func (w *WaitSet) AddSubscriptions(subs ...*Subscription)
type WaitSetEmpty ¶
type WaitSetEmpty struct {
// contains filtered or unexported fields
}
WaitSetEmpty Given rcl_wait_set_t is empty return code.
type WaitSetFull ¶
type WaitSetFull struct {
// contains filtered or unexported fields
}
WaitSetFull Given rcl_wait_set_t is full return code.
type WaitSetInvalid ¶
type WaitSetInvalid struct {
// contains filtered or unexported fields
}
WaitSetInvalid rcl wait and wait set specific ret codes in 9XXInvalid rcl_wait_set_t given return code.
type WrongLexeme ¶
type WrongLexeme struct {
// contains filtered or unexported fields
}
WrongLexeme Expected one type of lexeme but got another
Source Files ¶
Directories ¶
Path | Synopsis |
---|---|
These types implement the rosidl_runtime_c primitive types handling semantics.
|
These types implement the rosidl_runtime_c primitive types handling semantics. |