Documentation
¶
Index ¶
Constants ¶
View Source
const ( SimpleStatePending uint8 = 0 SimpleStateActive uint8 = 1 SimpleStateDone uint8 = 2 )
Variables ¶
This section is empty.
Functions ¶
This section is empty.
Types ¶
type Action ¶
type Action interface {
GetActionGoal() ActionGoal
GetActionFeedback() ActionFeedback
GetActionResult() ActionResult
}
type ActionClient ¶
type ActionClient interface {
WaitForServer(timeout ros.Duration) bool
SendGoal(goal ros.Message, transitionCallback interface{}, feedbackCallback interface{}) ClientGoalHandler
CancelAllGoals()
CancelAllGoalsBeforeTime(stamp ros.Time)
}
func NewActionClient ¶
func NewActionClient(node ros.Node, action string, actionType ActionType) ActionClient
type ActionFeedback ¶
type ActionFeedback interface {
ros.Message
GetHeader() std_msgs.Header
GetStatus() actionlib_msgs.GoalStatus
GetFeedback() ros.Message
SetHeader(std_msgs.Header)
SetStatus(actionlib_msgs.GoalStatus)
SetFeedback(ros.Message)
}
type ActionGoal ¶
type ActionResult ¶
type ActionResult interface {
ros.Message
GetHeader() std_msgs.Header
GetStatus() actionlib_msgs.GoalStatus
GetResult() ros.Message
SetHeader(std_msgs.Header)
SetStatus(actionlib_msgs.GoalStatus)
SetResult(ros.Message)
}
type ActionServer ¶
type ActionServer interface {
Start()
Shutdown()
PublishResult(status actionlib_msgs.GoalStatus, result ros.Message)
PublishFeedback(status actionlib_msgs.GoalStatus, feedback ros.Message)
PublishStatus()
RegisterGoalCallback(interface{})
RegisterCancelCallback(interface{})
}
func NewActionServer ¶
func NewActionServer(node ros.Node, action string, actionType ActionType, goalCb, cancelCb interface{}, autoStart bool) ActionServer
type ActionType ¶
type ActionType interface {
MD5Sum() string
Name() string
GoalType() ros.MessageType
FeedbackType() ros.MessageType
ResultType() ros.MessageType
NewAction() Action
}
type ClientGoalHandler ¶
type ServerGoalHandler ¶
type ServerGoalHandler interface {
SetAccepted(string) error
SetCancelled(ros.Message, string) error
SetRejected(ros.Message, string) error
SetAborted(ros.Message, string) error
SetSucceeded(ros.Message, string) error
SetCancelRequested() bool
PublishFeedback(ros.Message)
GetGoal() ros.Message
GetGoalId() actionlib_msgs.GoalID
GetGoalStatus() actionlib_msgs.GoalStatus
Equal(ServerGoalHandler) bool
NotEqual(ServerGoalHandler) bool
Hash() uint32
GetHandlerDestructionTime() ros.Time
SetHandlerDestructionTime(ros.Time)
}
func NewServerGoalHandlerWithGoal ¶
func NewServerGoalHandlerWithGoal(as ActionServer, goal ActionGoal) ServerGoalHandler
func NewServerGoalHandlerWithGoalId ¶
func NewServerGoalHandlerWithGoalId(as ActionServer, goalID *actionlib_msgs.GoalID) ServerGoalHandler
type SimpleActionClient ¶
type SimpleActionClient interface {
SendGoal(goal ros.Message, doneCb, activeCb, feedbackCb interface{})
SendGoalAndWait(goal ros.Message, executeTimeout, preeptTimeout ros.Duration) (uint8, error)
WaitForServer(timeout ros.Duration) bool
WaitForResult(timeout ros.Duration) bool
GetResult() (ros.Message, error)
GetState() (uint8, error)
GetGoalStatusText() (string, error)
CancelAllGoals()
CancelAllGoalsBeforeTime(stamp ros.Time)
CancelGoal() error
StopTrackingGoal()
}
func NewSimpleActionClient ¶
func NewSimpleActionClient(node ros.Node, action string, actionType ActionType) SimpleActionClient
type SimpleActionServer ¶
type SimpleActionServer interface {
Start()
IsNewGoalAvailable() bool
IsPreemptRequested() bool
IsActive() bool
SetSucceeded(result ros.Message, text string) error
SetAborted(result ros.Message, text string) error
SetPreempted(result ros.Message, text string) error
AcceptNewGoal() (ros.Message, error)
PublishFeedback(feedback ros.Message)
GetDefaultResult() ros.Message
RegisterGoalCallback(callback interface{}) error
RegisterPreemptCallback(callback interface{})
}
func NewSimpleActionServer ¶
func NewSimpleActionServer(node ros.Node, action string, actionType ActionType, executeCb interface{}, autoStart bool) SimpleActionServer
Click to show internal directories.
Click to hide internal directories.