Calling the DoObjectiveSequence
Action
PROCEED AT YOUR OWN RISK!
If you call and lose the goal handle for the DoObjectiveSequence
action, you will no longer be able to cancel the running objective.
If the objective has no end condition (and runs indefinitely) you will have to use the web UI to cancel the objective, or restart MoveIt Pro.
The DoObjectiveSequence
action is used to execute an objective, but the user is responsible for handling the goal state and possible error codes.
It is most useful for a custom ROS application to interface directly with MoveIt Pro's objective server, allowing you to control exactly when to launch and cancel an objective.
Example Usage
This example uses the rosbridge
API
The following code snippet demonstrates how to call the DoObjectiveSequence
action:
import roslibpy
import roslibpy.actionlib
# Host IP changes, the port is always 3201
client = roslibpy.Ros(host='localhost', port=3201)
# Define the action client
action = roslibpy.actionlib.ActionClient(client, '/do_objective', 'moveit_studio_sdk_msgs/action/DoObjectiveSequence')
# Define the goal (objective) message
goal = roslibpy.actionlib.Goal(action, roslibpy.Message({"objective_name" : "Close Gripper"}))
# Send the goal (objective)
goal.send()
# No timeout so we wait for a result
result = goal.wait()
action.dispose()
print('Error code: {}'.format(result['error_code']))
print('Error message: {}'.format(result['error_message']))
A list of all Error Codes can be found at the MoveIt Messages Documentation