Actionlib functions
ROS.actionlib.SimpleActionClient
ROS.actionlib.SimpleActionClient
ROS.actionlib.SimpleActionServer
ROS.actionlib.SimpleActionServer
ROS.actionlib.acceptNewGoal
ROS.actionlib.cancelAllGoals
ROS.actionlib.cancelGoal
ROS.actionlib.getResult
ROS.actionlib.getState
ROS.actionlib.getText
ROS.actionlib.isActive
ROS.actionlib.isDone
ROS.actionlib.isNewGoalAvailable
ROS.actionlib.isPreemptRequested
ROS.actionlib.isServerConnected
ROS.actionlib.publishFeedback
ROS.actionlib.registerGoalCallback
ROS.actionlib.registerPreemptCallback
ROS.actionlib.sendGoal
ROS.actionlib.sendGoalAndWait
ROS.actionlib.setAborted
ROS.actionlib.setAborted
ROS.actionlib.setPreempted
ROS.actionlib.setPreempted
ROS.actionlib.setSucceeded
ROS.actionlib.setSucceeded
ROS.actionlib.shutdown
ROS.actionlib.start
ROS.actionlib.stopTrackingGoal
ROS.actionlib.toString
ROS.actionlib.waitForResult
ROS.actionlib.waitForResult
ROS.actionlib.waitForServer
ROS.actionlib.waitForServer
ROS.actionlib.SimpleActionClient
— MethodSimpleActionClient(name::String, action_spec, spin::Bool)
Simple constructor.
ROS.actionlib.SimpleActionClient
— MethodSimpleActionClient(name::String, action_spec)
Simple constructor.
ROS.actionlib.SimpleActionServer
— MethodSimpleActionServer(name::String, action_spec, auto_start::Bool)
Constructor for a SimpleActionServer.
ROS.actionlib.SimpleActionServer
— MethodSimpleActionServer(name::String, action_spec)
Constructor for a SimpleActionServer.
ROS.actionlib.acceptNewGoal
— MethodacceptNewGoal(action_server)
Accepts a new goal when one is available. The status of this goal is set to active upon acceptance, and the status of any previously active goal is set to preempted. Preempts received for the new goal between checking if isNewGoalAvailable or invocation of a goal callback and the acceptNewGoal call will not trigger a preempt callback. This means, isPreemptRequested should be called after accepting the goal even for callback-based implementations to make sure the new goal does not have a pending preempt request.
ROS.actionlib.cancelAllGoals
— MethodcancelAllGoals(action_client)
Cancel all goals currently running on the action server.
ROS.actionlib.cancelGoal
— MethodcancelGoal(action_client)
Cancel the goal that we are currently pursuing.
ROS.actionlib.getResult
— MethodgetResult(action_client)
Get the Result of the current goal.
ROS.actionlib.getState
— MethodgetState(action_client)
Get the state information for this goal.
ROS.actionlib.getText
— MethodgetText(state)
Returns the text field of the state.
ROS.actionlib.isActive
— MethodisActive(action_server)
Allows polling implementations to query about the status of the current goal.
ROS.actionlib.isDone
— MethodisDone(state)
Determine if goal is done executing (ie. reached a terminal state).
ROS.actionlib.isNewGoalAvailable
— MethodisNewGoalAvailable(action_server)
Allows polling implementations to query about the availability of a new goal.
ROS.actionlib.isPreemptRequested
— MethodisPreemptRequested(action_server)
Allows polling implementations to query about preempt requests.
ROS.actionlib.isServerConnected
— MethodisServerConnected(action_client)
Checks if the action client is successfully connected to the action server.
ROS.actionlib.publishFeedback
— MethodpublishFeedback(action_server, feedback)
Publishes feedback for a given goal.
ROS.actionlib.registerGoalCallback
— MethodregisterGoalCallback(action_server, callback)
Allows users to register a callback to be invoked when a new goal is available.
ROS.actionlib.registerPreemptCallback
— MethodregisterPreemptCallback(action_server, callback)
Allows users to register a callback to be invoked when a new preempt request is available.
ROS.actionlib.sendGoal
— MethodsendGoal(action_client, goal)
Sends a goal to the ActionServer, and also registers callbacks.
ROS.actionlib.sendGoalAndWait
— MethodsendGoalAndWait(action_client, goal, ex_timeout, pr_timeout)
Sends a goal to the ActionServer, and waits until the goal completes or a timeout is exceeded.
ROS.actionlib.setAborted
— MethodsetAborted(action_server, result, text::String)
Sets the status of the active goal to aborted.
ROS.actionlib.setAborted
— MethodsetAborted(action_server)
Sets the status of the active goal to aborted.
ROS.actionlib.setPreempted
— MethodsetPreempted(action_server, result, text::String)
Sets the status of the active goal to preempted.
ROS.actionlib.setPreempted
— MethodsetPreempted(action_server)
Sets the status of the active goal to preempted.
ROS.actionlib.setSucceeded
— MethodsetSucceeded(action_server, result, text::String)
Sets the status of the active goal to succeeded.
ROS.actionlib.setSucceeded
— MethodsetSucceeded(action_server)
Sets the status of the active goal to succeeded.
ROS.actionlib.shutdown
— Methodshutdown(action_server)
Explicitly shutdown the action server.
ROS.actionlib.start
— Methodstart(action_server)
Explicitly start the action server, used it auto_start is set to false.
ROS.actionlib.stopTrackingGoal
— MethodstopTrackingGoal(action_client)
Stops tracking the state of the current goal. Unregisters this goal's callbacks.
ROS.actionlib.toString
— MethodtoString(state)
Convert the state to a string. Useful when printing debugging information.
ROS.actionlib.waitForResult
— MethodwaitForResult(action_client, timeout)
Blocks until this goal finishes.
ROS.actionlib.waitForResult
— MethodwaitForResult(action_client)
Blocks until this goal finishes.
ROS.actionlib.waitForServer
— MethodwaitForServer(action_client, timeout)
Waits for the ActionServer to connect to this client.
ROS.actionlib.waitForServer
— MethodwaitForServer(action_client)
Waits for the ActionServer to connect to this client.