Migration to 2.0.0

There have been significant changes in the 2.0.0 release for MoveIt Studio. Here is the list of modifications required to use the latest changes in custom Behaviors, Objectives, or workspaces. These changes are required for moving from any previous v1 version to the v2 release.

Use the latest Docker Services specifications

As part of the changeset for 2.0.0, PickNik has created a publicly available example site configuration and user workspace available on GitHub. Refer to the services specifications and variables in the docker-compose.yaml and .env files for the most up-to-date information.

Additional information on using the MoveIt Studio containers is available in Advanced Launch Configurations.

Besides improvements for stability, starting and stopping the application, and additional environment variables, we have added two new services for interacting with custom workspaces (see Mounting a User Workspace):

  • The workspace_builder for compiling custom user workspaces on startup.

  • The workspace_test for running unit tests in the custom user workspace.

To use the latest changes, you must resolve the differences in your local docker-compose.yaml file, as well as set the STUDIO_DOCKER_TAG to 2.0.0 in your local environment.

Using a custom overlay for your workspace

In addition to compiling a custom user space on startup, we have developed a standard for building custom workspaces using MoveIt Studio binary images. We recommend this approach, particularly when developing custom Behaviors that require more fine-grained developer tooling.

Refer to Create Overlay Docker Images for more information.

Upgrade to BehaviorTree.CPP v4

We have migrated BehaviorTree to the recently released v4 (up from v3). For a complete guide on changes for your existing packages, Objectives, and Behaviors, refer to the Migration Guide.

A brief summary of the required changes:

  • Include behaviortree_cpp as a build dependency, in place of behaviortree_cpp_v3.

  • Update included headers, for example:

    // Replace v3 header
    #include <behaviortree_cpp_v3/bt_factory.h>
    
    // With the v4 header
    #include <behaviortree_cpp/bt_factory.h>
    
  • Apply required XML updates to any saved Objectives using the provided BehaviorTree.CPP conversion script. This script will can be used to update existing objectives, though the changes can also be applied manually:

    • Add BTCPP_format="4" to the root XML parameters of existing Objectives. For example:

      <?xml version="1.0"?>
      <!-- Specify the format -->
      <root BTCPP_format="4" main_tree_to_execute="Clear Snapshot">
         <!-- ////////// -->
         <BehaviorTree ID="Clear Snapshot" _description="Clear the point cloud snapshot">
            <Action ID="ClearSnapshot" />
         </BehaviorTree>
      </root>
      
    • Replace SubTreePlus with SubTree.

    • Use Script instead of SetBlackboard.

      
      

      <!– Replace SetBlackboard –> <Action ID=”SetBlackboard” output_key=”random_variable” value=”true”/>

      <!– With Script –> <Script code=”random_variable:=true” />

    • Use Precondition instead of BlackboardCheck<type>

      
      

      <!– Replace BlackboardCheckString –> <Decorator ID=”BlackboardCheckString” value_A=”{random_variable}” value_B=”true” return_on_mismatch=”SUCCESS”>

      <!– With Precondition –> <Precondition if=”random_variable” else=”SUCCESS”>

Ensure joint limits are set in your MoveIt configuration

In the latest release we have bumped to MoveIt 2.7.0. To use the latest motion planning capabilities, ensure you have configured and set appropriate joint limits for your robot. Refer to the example in the public user workspace. Then, ensure that the moveit_params.joint_limits option is set in your robot’s site configuration:

moveit_params:
  joint_limits:
    package: "picknik_ur_base_config"
    path: "config/moveit/joint_limits.yaml"

Expanded functionality in the built-in logger

The built in failure_logger has been replaced with a more generic logger. We have provided built-in functions to log at the FAILURE, WARNING, and INFO levels, with optional functionality to delay message publication until the completion of an Objective.

The tutorials have examples of how to use the built-in logger. See the 4. Edit the Custom Behavior Source Code tutorial.

For a detailed description of the new object, refer to the online documentation for the Logger classes.

Ensure nodes model files are up to date

The list of available built-in Behaviors, or their port names, parameters, or defaults have change in this version. Ensure you are using the most up-to-date information for both the standard_tree_nodes_model.xml and the MoveIt Studio core tree_nodes_model.xml by pulling the latest changes from the public workspace.

For additional information on built-in MoveIt Studio behaviors refer to the List of Core Behaviors.

Improved functionality for the “Take Snapshot” Objective

Previously, the “Take Snapshot” Objective relied on asynchronous calls to update both the MoveIt planning scene, as well as the point clouds rendering in the MoveIt Studio user interface. We have added several new behaviors to ensure calls are completed more reliably.

We recommend adding the new UpdatePlanningSceneService and SendPointCloudToUI Behaviors to your tree_nodes_model.xml:

<Action ID="UpdatePlanningSceneService">
   <metadata subcategory="Perception"/>
   <description>
         <p>
            Updates the planning scene's collision octree using the provided point cloud, and waits until the octree has finished updating.
         </p>
   </description>
   <input_port name="point_cloud" default="{point_cloud}">Point cloud in sensor_msgs::msg::PointCloud2 format.</input_port>
   <input_port name="point_cloud_service" default="/point_cloud_service">Name of the service advertised by the PointCloudServiceOctomapUpdater MoveIt plugin.</input_port>
</Action>

<Action ID="SendPointCloudToUI">
   <metadata subcategory="Perception"/>
   <description>
         <p>
            Given a point cloud, filter it using MoveIt's settings for that sensor, convert it to ASCII PCD format, and publish it on a topic.
         </p>
         <p>
            The UUID parameter can be used to track the pointcloud request through to other behaviors, if required. It is an optional input port, and if unset then the published message will have an empty string in its UUID field. Note: no validation is done on the value of the UUID, so any string that is provided (including the empty string) will be set on the output port.
         </p>
   </description>
   <input_port name="point_cloud" default="{point_cloud}">Point cloud in sensor_msgs::msg::PointCloud2 format.</input_port>
   <input_port name="sensor_name" default="scene_scan_camera">The name of the sensor the point cloud was generated from</input_port>
   <input_port name="point_cloud_uuid" default="">Optional identifier for the request to be published to the pcd_topic</input_port>
   <input_port name="pcd_topic" default="/pcd_pointcloud_captures">Topic the pcd formatted point cloud is published to.</input_port>
</Action>

Then update your “Take Snapshot” Objective to use the new Behaviors:

<?xml version="1.0"?>
<root BTCPP_format="4" main_tree_to_execute="Take Snapshot">
   <!-- ////////// -->
   <BehaviorTree ID="Take Snapshot" _description="Take a point cloud snapshot and add to collision scene">
      <Sequence>
            <Action ID="GetPointCloud" target_point_cloud_topic="/wrist_mounted_camera/depth/color/points" uuid="{take_snapshot.uuid}" point_cloud="{point_cloud}" point_cloud_uuid="{request_uuid}" />
            <Action ID="UpdatePlanningSceneService" point_cloud="{point_cloud}" point_cloud_service="/point_cloud_service"/>
            <Action ID="SendPointCloudToUI" point_cloud="{point_cloud}" sensor_name="scene_scan_camera" pcd_topic="/pcd_pointcloud_captures" point_cloud_uuid="{request_uuid}"/>
      </Sequence>
   </BehaviorTree>
</root>