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
Running an Objective with a Behavior Tree string
MoveIt Pro has been updated such that you can now send an objective via a string directly to MoveIt Pro!
When you have an instance of MoveIt Pro running, attach a shell to the Docker container by running moveit_pro shell
.
From the shell, run the following command:
ros2 action send_goal /do_objective moveit_studio_sdk_msgs/action/DoObjectiveSequence '
objective_xml_string: |
<root BTCPP_format="4" main_tree_to_execute="test simple">
<BehaviorTree ID="test simple">
<Control ID="Sequence" name="TopLevelSequence">
<Action ID="AlwaysSuccess"/>
</Control>
</BehaviorTree>
</root>
'
You should see the Objective successfully run in the UI.
It is also possible to run an objective or subtree that already exists while also remapping ports!
Below, is an objective that wraps the Move To Waypoint
subtree.
The waypoint_name
port is mapped to Look at Table
(This objective assumes you are running the lab_sim
config).
Try running the objective, you should see the arm move to the Look at Table
waypoint.
ros2 action send_goal /do_objective moveit_studio_sdk_msgs/action/DoObjectiveSequence '
objective_xml_string: |
<root BTCPP_format="4" main_tree_to_execute="Move To Waypoint Remapped">
<BehaviorTree ID="Move To Waypoint Remapped">
<Control ID="Sequence" name="TopLevelSequence">
<SubTree
ID="Move to Waypoint"
_collapsed="true"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
use_all_planners="false"
/>
</Control>
</BehaviorTree>
</root>
'
Now if you take the same code above but set waypoint_name
to Park Far Right
, you should see the arm move all the way to the right.
This functionality gives you the ability to invoke MoveIt Pro objectives and behaviors with more flexibility.