MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors Namespace Reference

Namespaces

 affordance_transforms
 
 check_for_error_utils
 
 wrench_measurement
 

Classes

class  ActivateControllers
 Activate controllers, whose names are set by the "controller_names" parameter. More...
 
class  AddSubframeToObject
 Annotates an input GraspableObject with an input Pose and Pose ID. More...
 
class  AddVirtualObjectToPlanningScene
 Uses the service provided by the ApplyPlanningScene MoveGroup capability plugin to add a virtual collision object to the planning scene. A virtual collision object is only forbidden to collide with the robot. More...
 
class  AppendOrientationConstraint
 Appends an orientation constraint (based on the values specified in the input port's yaml file) to an existing constraints message. More...
 
class  AttachTool
 This Behavior sends a request to attach a tool to a robot for motion planning purposes. More...
 
class  AveragePoseStamped
 This Behavior calculates the running average of incoming Pose Stamped ROS messages. More...
 
class  BiasedCoinFlip
 Simulates flipping a biased coin with the specified probability of success provided via the input port. More...
 
class  BreakpointSubscriber
 A behavior that subscribes to a topic that can be used for pausing an objective during execution to allow introspection. This behavior will listen on the configured topic for a True/False message which will cause it to continue or abort from a breakpoint that is included in an objective. More...
 
class  CalculatePoseOffset
 Calculates the offset transform from source_pose to destination_pose. This can be used to measure the distance between two poses and returns the result relative to the source_pose. More...
 
class  CallTriggerService
 Call a service that accepts a std_srvs/srv/Trigger message. The name of the service is set through the "service_name" parameter. More...
 
class  CreateGraspableObject
 
class  CreateJointState
 Create a sensor_msgs::msg::JointState and writes it to the Blackboard. More...
 
class  CreateStampedPose
 Create a geometry_msgs::msg::PoseStamped and writes it to the Blackboard. More...
 
class  CreateStampedTwist
 Create a geometry_msgs::msg::TwistStamped and writes it to the Blackboard. More...
 
class  CreateStampedWrench
 Create a geometry_msgs::msg::WrenchStamped and writes it to the Blackboard. More...
 
class  CreateStationaryTrajectory
 This behavior creates a stationary trajectory of specified duration at the provided JointState ROS message. More...
 
class  DetachTool
 This Behavior sends a request to detach a tool from a robot for motion planning purposes. More...
 
class  DoTeleoperateAction
 Starts teleoperation by sending a goal to the teleoperation action server in the web UI. More...
 
class  EditWaypoint
 Use the /edit_waypoints service to save the robot's current state as a new named waypoint or erase an existing waypoint. The name of the waypoint to save or delete is set through the "waypoint_name" behavior parameter. The operation to perform on the waypoint is set through the "waypoint_operation" behavior parameter, which must be set to either "save" or "erase". More...
 
class  ExecuteFollowJointTrajectory
 Accepts a JointTrajectory message via an input data port, and executes it by sending a goal to the specified FollowJointTrajectory action server. More...
 
class  ExecuteTrajectoryWithAdmittance
 Accepts a JointTrajectory message via an input data port, and executes it by sending a goal to a Joint Trajectory With Admittance controller (JTAC). More...
 
class  ExtractGraspableObjectPose
 Changes an input GraspableObject into a PoseStamped by getting its pose and its ID. More...
 
class  ForEach
 A class for creating a behavior tree decorator node to iterate through a vector of items. More...
 
class  ForceExceedsThreshold
 Monitors wrench messages published to topic, and returns SUCCESS if the magnitude of the wrench measurements exceeds a force threshold for a minimum number of consecutive readings. More...
 
class  GenerateCoveragePath
 Creates a zig-zag path for a robot end-effector to follow, to cover a given area. More...
 
class  GenerateObjectsInBox
 
struct  ObjectWithDistance
 Associates a GraspableObject with a distance metric. More...
 
class  GetClosestObjectToPose
 Given a collection of GraspableObjects, find the one that's closest to the provided pose. More...
 
class  GetCurrentPlanningScene
 Get the current planning scene state from the MoveIt PlanningSceneMonitor via service request. More...
 
class  GetGraspAndTwistSubframes
 Given an input PoseStamped representing a grasp pose selected on an object, get the three Subframes that define a Grasp Screw Motion (grab and twist about an axis) where the object is grabbed and rotated by grasp_rotation_z_radians amount. More...
 
class  GetLatestTransform
 Gets the latest transform from the robot model root to a frame specified as an input parameter to this behavior. More...
 
class  GetMoveAlongArcSubframes
 Given a PoseStamped for a grasp pose, and a vector of two PoseStampeds for the axis of the arc, calculates the subframes needed for motion along an arc. The arc radius is the distance between the grasp point and the arc (hinge) axis. More...
 
class  GetParameterValueFromUser
 This is a template class to get parameter values which are stored in a map in the Objective Server node. The map contains parameter overrides which are specified when creating the DoObjectiveSequence goal. Given a parameter name, send a service request to the Objective Server to retrieve user input value for the parameter named parameter_name. More...
 
class  GetStringFromUser
 Given a parameter name, send a service request to the Objective Server to retrieve user input value of type string for the parameter named parameter_name. More...
 
class  GetRobotJointState
 This behavior extracts a ROS sensor_msgs/JointState message from a a planning scene object. More...
 
class  InitializeMotionConstraints
 Creates a shared pointer to a new moveit_msgs::msg::Constraints and writes it to the Blackboard. More...
 
class  IsConstraintSatisfied
 Check if the robot's current state satisfies a visibility kinematic constraint relative to an object. More...
 
class  IsUserAvailable
 Checks for the presence of a user interface by checking if the /trajectory_bridge ROS node exists. More...
 
class  LoadObjectiveParameters
 Loads the configuration parameters for a given objective. The configuration file name is given as an input port parameters to this behavior. The parameters are loaded once per objective execution. To reload the parameter from the file, just execute the objective again. More...
 
class  LogMessage
 Logs a user specified message via the LoggerROS class. ROS 2 log severity of message specified by log_level. More...
 
class  ModifyObjectInPlanningScene
 Uses the service provided by the ApplyPlanningScene MoveGroup capability plugin to add a collision object representing a GraspableObject to the planning scene. More...
 
class  MoveGripperAction
 Actuate a gripper through its driver node's GripperCommand action. Given the name of the action topic and a target gripper position, move the gripper to the specified position. More...
 
class  PlanCartesianPath
 Given a Cartesian-space path, plan a joint-space trajectory to move the robot tip along the path. More...
 
class  PlanToJointGoal
 Given a joint-space goal, plan a joint-space trajectory to reach the goal. More...
 
class  PublishEmpty
 Publish a std_msgs::msg::Empty message to a topic. More...
 
class  PublishStaticFrame
 Publishes a static transform into the tf2 buffer. More...
 
class  PublishString
 Publish a std_msgs::msg::String message to a topic. More...
 
class  PublishVelocityForceCommand
 Publishes a static transform into the tf2 buffer. More...
 
class  ReadTextFileAsString
 Read the contents of a text file and output the contents as a std::string. More...
 
class  CoreBehaviorsLoader
 
class  RemoveCollisionObjectFromPlanningScene
 Uses the service provided by the ApplyPlanningScene MoveGroup capability plugin to remove a collision object from the planning scene. The CollisionObject that has an ID that matches object_id has its operation field set to REMOVE. If there is no CollisionObject with object_id, the behavior returns an error. More...
 
class  ResetPlanningSceneObjects
 Uses the service provided by the ApplyPlanningScene MoveGroup capability plugin to remove all objects which were added to the planning scene, including objects that are attached to the robot. More...
 
class  RetrieveWaypoint
 Given a named waypoint, sends a service request to the Agent WaypointManager to retrieve the joint state associated with that waypoint. More...
 
class  SaveCurrentState
 Use the /get_planning_scene service from move_group to save the robot's current state. More...
 
class  SetAdmittanceParameters
 Sets admittance parameters to be used in the 'ExecuteTrajectoryWithAdmittance' Behavior. More...
 
class  SolveIKQueries
 
class  StopwatchBegin
 Saves the current epoch time as a timepoint to a data port. More...
 
class  StopwatchEnd
 Measure the difference between an input timepoint and the current timepoint, and emit a log message which states the time elapsed. More...
 
class  TransformPose
 Transforms a stamped pose given an input translation and orientation. More...
 
class  TransformPoseFrame
 Transforms the reference frame of an input stamped pose to the frame specified by a frame ID, along with the position/orientation transformation that entails. More...
 
class  TransformPoseFromYaml
 Transforms a stamped pose given an input yaml file that contains the translation and orientation that should be applied to the input. NOTE: The pose_parameters port is normally provided by a LoadObjectiveParameter Behavior. More...
 
class  TransformPoseWithPose
 Transforms an input stamped pose with the transform specified by another stamped pose. More...
 
class  AdjustPoseWithIMarker
 Requests a user to manually adjust a collection of poses using interactive markers in the UI. More...
 
class  GetPointsFromUser
 Requests a set of named points from the user by switching the view and displaying a sequence of prompts in the UI. More...
 
class  GetTextFromUser
 Gets text from user by sending a list of prompts with default values for each prompt. More...
 
class  RetrieveJointStateParameter
 Retrieves a joint state from the MoveIt Pro parameter manager node. More...
 
class  RetrievePoseParameter
 Retrieves a stamped pose from the MoveIt Pro parameter manager node. More...
 
class  SwitchUIPrimaryView
 Switches the primary view in the MoveIt Studio Developer Tool. More...
 
class  ValidateTrajectory
 Checks if a joint trajectory is valid, given a PlanningScene. More...
 
class  WaitForDuration
 Wait for a specified duration before succeeding. More...
 
class  WriteCalibratedPoseToYaml
 Write pose (x,y,z, roll, pitch, yaw) to YAML file. This behavior is meant to be called after the Calibrate Pose Action. TODO: Make this behavior more generic. Note: The behavior saves the calibrated_pose into the ~/.config/moveit_pro/calibration folder. More...
 
class  ExecuteMTCTask
 Takes an MTC Solution message via an input data port, and executes the lowest-cost trajectory in that Solution using the MTC ExecuteTaskSolution MoveGroup capability's /execute_task_solution action server. More...
 
class  InitializeMTCTask
 Creates a shared pointer to a new MTC Task object, populates it with global settings (for example, the names of controllers to enable by default when executing trajectories planned by this Task), and sets it as an output data port. More...
 
class  PlanMTCTask
 Takes a shared pointer to an existing MTC Task object via an input data port, plans the Task, and sets the solution with the lowest overall cost as an output data port. A service client sends over all the solutions to the MTC Solution Manager node which can be used for debugging. More...
 
class  PushToSolutionQueue
 Push a new MTC solution to the solution queue. More...
 
class  MTCCoreBehaviorsLoader
 
class  SplitMTCSolution
 Given an MTC Solution message and an index, create two new MTC Solution messages by splitting the subtrajectories of the input Solution at the specified index. Outputs the new Solutions onto output data ports. More...
 
class  WaitAndPopSolutionQueue
 Pops the MTC solution queue to get the next solution to be processed. More...
 
class  WaitForUserTrajectoryApproval
 Takes an MTC Solution message via an input data port, and publishes it to the /preview_solution topic. Creates a SetBool service server on the /execute_behavior_solution topic and waits to receive a request containing data: true before succeeding. More...
 
class  MTCTaskSetupBehaviorsLoader
 
class  SetupMTCApproachGrasp
 Given an existing MTC Task object and a target object, appends MTC stages to describe a motion plan to approach the object. More...
 
class  SetupMTCAttachOrDetachObject
 This is the base class for SetupMTCAttachObject and SetupMTCDetachObject. More...
 
class  SetupMTCAttachObject
 Add an MTC Stage to an MTC Task that attaches an object to the named robot frame. More...
 
class  SetupMTCDetachObject
 Add an MTC Stage to an MTC Task that detaches an object from the named robot frame. More...
 
class  SetupMTCCartesianMoveToJointState
 Given an existing MTC Task object and a joint state, appends MTC stages to describe a cartesian motion plan to that joint state. More...
 
class  SetupMTCCartesianSequence
 Given an existing MTC Task object and a sequence of target poses, appends MTC stages to plan a sequence of cartesian motions between the poses. More...
 
class  SetupMTCConnectWithTrajectory
 Append a MTC stage to connect the end state of the previous stage with the start state of the next stage using a freespace trajectory. More...
 
class  SetupMTCCurrentState
 Given an existing MTC Task object, appends an MTC CurrentState Stage to the Task. More...
 
class  SetupMTCFixedJointState
 Given an existing MTC Task object, appends an MTC FixedState Stage to the Task. More...
 
class  SetupMTCFromSolution
 Given an existing MTC Task object, appends an MTC Stage to the Task that initializes it with the final planning scene of a given solution. More...
 
class  SetupMTCGenerateCuboidGrasps
 Given an existing MTC Task object and a target object, appends MTC stages to generate cuboid grasp poses. More...
 
class  SetupMTCGenerateVacuumGrasps
 Given an existing MTC Task object and a target object, appends MTC stages to generate vacuum grasp poses on its planar surfaces. More...
 
class  SetupMTCGraspAndTwistThenMoveAlongArcPush
 Configures MTC stages to grasp a location, rotate the end-effector about an axis to turn the grasp point (for example a handle), and then push the end-effector away from the robot base while still grasping (for example to open a door). More...
 
class  SetupMTCGraspThenMoveAlongArcPull
 Configures MTC stages to perform a motion that can be parameterized as a grasp followed by a pulling motion in a screw-trajectory (a circular arc). Examples in practice include opening pull doors and drawers. More...
 
class  SetupMTCIgnoreCollisionsBetweenObjects
 Given an MTC Task, append an MTC Stage that modifies the planning scene's Allowed Collision Matrix to permit or forbid collision between a set of objects while planning subsequent Stages. More...
 
class  SetupMTCInterpolateToJointState
 Given an existing MTC Task object and a joint state, appends MTC stages to describe a joint-interpolated motion plan to that joint state. More...
 
class  SetupMTCMoveAlongFrameAxis
 Given an existing MTC Task object, append a MTC MoveRelative stage to perform a cartesian motion along an axis. More...
 
class  SetupMTCMoveToJointState
 Given an existing MTC Task object and a joint state, appends MTC stages to describe a freespace motion plan to that joint state. More...
 
class  SetupMTCMoveToNamedState
 Given an existing MTC Task object and the name of a known state, appends MTC stages to describe a freespace motion plan to that state. More...
 
class  SetupMTCMoveToPose
 Given an existing MTC Task object and a target pose, appends MTC stages to describe a freespace motion plan to that target pose. More...
 
class  SetupMTCPickObject
 Given an existing MTC Task object and a target grasp pose, appends MTC stages to describe a motion plan to approach, grasp and lift an object at that pose. More...
 
class  SetupMTCRetractFromGrasp
 Given an existing MTC Task object and a target object, appends MTC stages to describe a motion plan to retract after grasping the object. More...
 
class  SetupMTCUpdateGroupCollisionRule
 Given an MTC Task, append an MTC Stage that modifies the planning scene's Allowed Collision Matrix to permit or forbid collision between a planning scene object and the links of a named robot planning group while planning subsequent Stages. More...
 
class  SetupMTCUpdateObjectCollisionRule
 Add an MTC Stage to an MTC Task that makes following stages either allow or prohibit collision between a GraspableObject and another entity. The other entity can be either a named collision object in the planning scene or the links of a named robot planning group. More...
 
class  NavigateThroughPosesAction
 Calls an action server that uses nav2_msgs::action::NavigateThroughPoses and outputs feedback The NavigateThroughPoses action (ROS 2 Humble) does not produce a result. More...
 
class  NavigateToPoseAction
 Calls an action server that uses nav2_msgs::action::NavigateToPose and outputs feedback The NavigateToPose action (ROS 2 Humble) does not produce a result. More...
 
class  NavBehaviorsLoader
 
class  GetMeshNormalPoses
 Gets the normal vectors for a given mesh and returns the normal vector poses to the caller. More...
 
class  ServoBehaviorsLoader
 
class  ServoTowardsPose
 Move the tip at a velocity in closed loop towards a Cartesian target_pose, using Servo. More...
 
class  TeleoperateBase
 This is a special Behavior to enable manual teleoperation using MoveIt Servo through the Objective Server. More...
 
class  TeleoperateJointJog
 Specialization of TeleoperateBase for joint jog commands. More...
 
class  TeleoperateTwist
 Specialization of TeleoperateBase for Cartesian twist commands. More...
 
class  AddPointCloudToVector
 Appends a point cloud to a vector of point clouds. More...
 
class  CalibratePoseAction
 Calls a robot_calibration_msgs::action::CalibratePose action server and outputs the results on the calibrated_poses port. NOTE: For now this behavior only supports sending a single frame for calibration. More...
 
class  ShapeCompletionAction
 Calls an action server that uses moveit_studio_vision_msgs::action::ShapeCompletion interface and outputs the completed pointcloud given a partial or occluded pointcloud. More...
 
class  CheckCuboidSimilarity
 Check if two GraspableObjects are similar within some tolerance. More...
 
class  ClearSnapshot
 Sends a request to clear the existing Octomap and Pointcloud snapshots. More...
 
class  CropPointsInBox
 Given a point cloud and a box-shaped region of interest, create a new point cloud which contains only the points that are inside the region of interest. The dimensions and size of the region of interest are defined relative to its centroid. More...
 
class  CropPointsInSphere
 Given a point cloud and a sphere-shaped region of interest, create a new point cloud which contains only the points that are inside the region of interest. The dimensions and size of the region of interest are defined relative to its centroid. More...
 
class  DetectAprilTags
 Detects AprilTag markers from an image. More...
 
class  FindMaskedObjects
 Finds objects by segmenting a point cloud using a set of 2D mask images. More...
 
class  FindSingularCuboids
 Finds well-singulated cuboids supported by a surface within a point cloud. More...
 
class  FitLineSegmentToMask3D
 Finds the line segment that best fits a point cloud fragment. More...
 
class  GetCameraInfo
 Capture camera information. The name of the topic containing the camera information is set through the "topic_name" parameter, and the resulting information is available on the "message_out" output port. More...
 
class  GetDetectionPose
 Gets the stamped pose of an object detection given a label or ID, if one exists. More...
 
class  GetDoorHandlePose
 This class represents a behavior that can calculate the pose of a door lever handle along with its depth and length. The convention is that the Z-axis of the pose represents the axis of rotation of the handle. The X-axis points along the handle and points toward the door hinge. More...
 
class  GetGraspableObjectsFromMasks3D
 Finds objects in point cloud segments represented by 3D masks. More...
 
class  GetImage
 Capture an image. The name of the topic containing the image is set through the "topic_name" parameter, and the resulting image is available on the "message_out" output port. More...
 
class  GetMasks2DAction
 Calls an action server that uses moveit_studio_vision_msgs::action::GetMasks2D interface and outputs the results on the masks2d port. More...
 
class  GetMasks3DFromMasks2D
 Backprojects a number of image masks onto a point cloud with a camera model. More...
 
class  GetPointCloud
 Capture a point cloud. The name of the topic containing the point cloud is set through the "topic_name" parameter, and the resulting point cloud is available on the "message_out" output port. More...
 
class  GetPointCloudFromMask3D
 Gets the fragment of a point cloud for a 3D mask. More...
 
class  GetPoseFromPixelCoords
 Given an ordered point cloud and normalized pixel XY coordinates, outputs a stamped pose corresponding to a point normal to the selected coordinates. More...
 
class  GetSyncedImageAndPointCloud
 Get data from time-synchronized image and point cloud topics and populate them in output ports. More...
 
class  GetSyncedImages
 Get data from time-synchronized image topics and populate them in output ports. More...
 
class  LoadImageFromFile
 Loads an image from a file and writes it to an output data port. More...
 
class  LoadPointCloudFromFile
 Loads a point cloud from a .pcd or .stl file, optionally recolors it, and writes it to an output data port. More...
 
class  MergePointClouds
 Merges a number of input point clouds into a single one. More...
 
class  PublishPointCloud
 Publish a point cloud. More...
 
class  RegisterPointClouds
 Registers a target point cloud to a base point cloud and outputs the pose of the target point cloud relative to the origin of the base point cloud which aligns the target cloud with the base cloud. More...
 
class  VisionBehaviorsLoader
 
class  SaveImageToFile
 Save an image to disk as a .png file. The filename will follow the syntax of file_prefix_YYYYMMDD_HHMMSS.png. More...
 
class  SavePointCloudToFile
 Save a point cloud .pcd file to disk. The filename will follow the syntax of file_prefix_YYYYMMDD_HHMMSS.pcd. More...
 
class  SendPointCloudToUI
 Crop and filter a point cloud using MoveIt's sensor configuration, then publish it to a topic monitored by the UI. More...
 
class  TransformPointCloud
 Transforms a point cloud given an input pose in the same frame as the point cloud. More...
 
class  TransformPointCloudFrame
 Transforms a point cloud to a target coordinate frame. More...
 
class  UpdatePlanningSceneService
 Uses the service advertised by the PointCloudServiceOctomapUpdater plugin to apply a point cloud to the planning scene collision octomap and wait until the update has been applied. More...
 
class  PublishMarkers
 Publishes a set of markers to the UI for visualization. More...
 
class  VisualizeMesh
 Publishes a marker that contains a mesh path to the UI for visualization. More...
 
class  VisualizePath
 Publishes a marker array that contains a polyline representing a path. More...
 
class  VisualizePose
 Publishes a visualization marker that contains three lines composing a coordinate frame. More...
 
class  ActionClientBehaviorBase
 A base class for behaviors which need to send a goal to a ROS action client and wait for a result. If the behavior is halted before the action result is received, the action goal will be canceled. More...
 
class  AddToVector
 Pushes an object into a vector and sets the updated vector to the blackboard. More...
 
class  AsyncBehaviorBase
 A base class for behaviors which need to asynchronously run a function that might take a long time to complete. More...
 
struct  BehaviorContext
 The BehaviorContext struct contains shared resources that are common between all instances of Behaviors that inherit from moveit_studio::behaviors::SharedResourcesNode. More...
 
class  ClockInterfaceBase
 A base class which provides an interface for retrieving timepoints from a monotonic clock. More...
 
class  SteadyClockInterface
 Implementation of ClockInterfaceBase for std::chrono::steady_clock. More...
 
class  GetMessageFromTopicBehaviorBase
 Base class for Behaviors that get the latest message from a topic specified on an input data port and set that message to an output data port. More...
 
class  LoadMultipleFromYaml
 Loads types from a YAML file, and returns them as a vector in an output port. More...
 
class  LoadFromYaml
 Loads a type from a YAML file, and returns it in an output port. More...
 
class  PublisherInterfaceBase
 Defines an interface to a publisher that sends a message to a topic. More...
 
class  RclcppPublisherInterface
 Implementation of the publisher interface for a rclcpp publisher. More...
 
class  ResetVector
 Create an empty vector and set it to the blackboard. More...
 
class  SaveToYaml
 Save the contents of a ROS 2 message type to a YAML file in a specified namespace. Note: This Behavior template saves the pose into the ~/.config/moveit_pro/robot_config/objectives folder. More...
 
class  SendMessageToTopicBehaviorBase
 Base class for Behaviors that send a message to a topic. The message contents and topic name are specified as input ports. More...
 
class  ServiceClientBehaviorBase
 A base class for behaviors which need to send a request to a ROS service client and wait for a result. More...
 
class  ClientInterfaceBase
 Provides an interface to a service client that can send a single request at a time. WARNING - This class currently does not support calling syncSendRequest function asynchronously from multiple threads. More...
 
class  RclcppClientInterface
 Implements ClientInterfaceBase for the rclcpp service client. More...
 
class  SharedResourcesNode
 The SharedResourcesNode class provides a BehaviorContext object when constructing a BehaviorTree.Cpp node. More...
 
class  SharedResourcesNodeLoaderBase
 The SharedResourcesNodeLoaderBase class is a base class for Behavior loader plugins that register Behaviors inheriting from SharedResourcesNode. More...
 

Typedefs

using SetStringArray = moveit_studio_agent_msgs::srv::SetStringArray
 
using ApplyPlanningScene = moveit_msgs::srv::ApplyPlanningScene
 
using Trigger = std_srvs::srv::Trigger
 
using GetPlanningScene = moveit_msgs::srv::GetPlanningScene
 
using DoTeleoperate = moveit_studio_sdk_msgs::action::DoTeleoperate
 
using FollowJointTrajectory = control_msgs::action::FollowJointTrajectory
 
using RetrieveBehaviorParameter = moveit_studio_agent_msgs::srv::RetrieveBehaviorParameter
 
using GripperCommand = control_msgs::action::GripperCommand
 
using AdjustPose = moveit_studio_internal_msgs::srv::AdjustPose
 
using RequestPointsFromUser = moveit_studio_internal_msgs::srv::RequestPointsFromUser
 
using RequestTextFromUser = moveit_studio_internal_msgs::srv::RequestTextFromUser
 
using RetrieveJointState = moveit_studio_agent_msgs::srv::RetrieveJointState
 
using RetrievePose = moveit_studio_agent_msgs::srv::RetrievePose
 
using SwitchPrimaryView = moveit_studio_internal_msgs::srv::SwitchPrimaryView
 
using ExecuteTaskSolution = moveit_task_constructor_msgs::action::ExecuteTaskSolution
 
using StoreUidMap = moveit_studio_internal_msgs::srv::StoreUidMap
 
using NavigateThroughPoses = nav2_msgs::action::NavigateThroughPoses
 
using NavigateToPose = nav2_msgs::action::NavigateToPose
 
using CalibratePose = robot_calibration_msgs::action::CalibratePose
 
using ShapeCompletion = moveit_studio_vision_msgs::action::ShapeCompletion
 
using GetMasks2D = moveit_studio_vision_msgs::action::GetMasks2D
 
using SendPointCloud2 = moveit_studio_agent_msgs::srv::SendPointCloud2
 
using AttachToolSrv = moveit_studio_agent_msgs::srv::AttachTool
 
using DetachToolSrv = moveit_studio_agent_msgs::srv::DetachTool
 

Functions

moveit_msgs::srv::ApplyPlanningScene::Request createAddVirtualCollisionObjectToPlanningSceneRequest (const moveit_studio_vision_msgs::msg::GraspableObject &graspable_object, const moveit_msgs::msg::PlanningScene &planning_scene)
 Creates a ApplyPlanningScene::Request for adding a virtual collision object to the planning scene. More...
 
tl::expected< std::vector< Eigen::Isometry3d >, std::string > generateCoveragePath (const Eigen::Isometry3d &bottom_right_corner, const double width, const double height, const double stride_distance)
 Generates a zig-zag path for a robot end-effector to follow, to cover a given area. More...
 
tl::expected< std::vector< ObjectWithDistance >, std::string > calculateClosestObjectToPose (const tf2_ros::Buffer &buffer, const std::vector< moveit_studio_vision_msgs::msg::GraspableObject > &objects, const geometry_msgs::msg::PoseStamped &pose)
 Get the closest object to the provided pose. More...
 
tl::expected< ApplyPlanningScene::Request, std::string > createRemoveCollisionObjectFromPlanningSceneRequest (const std::string &object_id, moveit_msgs::msg::PlanningScene &planning_scene)
 
tl::expected< std::vector< moveit_task_constructor_msgs::msg::Solution >, std::string > splitSolutionAtIndex (const moveit_task_constructor_msgs::msg::Solution solution_in, const std::size_t index)
 Split an MTC Solution message in two by dividing its vector of subtrajectories at the specified index. More...
 
tl::expected< void, std::string > requestSwitchCommandType (std::shared_ptr< rclcpp::Client< moveit_msgs::srv::ServoCommandType >> client, std::shared_ptr< moveit_msgs::srv::ServoCommandType::Request > request)
 Send a request through a service client for a moveit_msgs::srv::ServoCommandType service and block until a response is received or a timeout limit is reached. More...
 
tl::expected< void, std::string > startServo (std::shared_ptr< rclcpp::Client< std_srvs::srv::SetBool >> client)
 Starts the servo node. More...
 
tl::expected< void, std::string > stopServo (std::shared_ptr< rclcpp::Client< std_srvs::srv::SetBool >> client)
 Stops the servo node. More...
 
tl::expected< bool, std::string > isObjectSimilar (const tf2_ros::Buffer &buffer, const moveit_studio_vision_msgs::msg::GraspableObject &input, const moveit_studio_vision_msgs::msg::GraspableObject &reference, const std::string &base_frame, const double distance_threshold, const double orientation_threshold)
 Helper function to check if two GraspableObjects are similar within some tolerance. More...
 
tl::expected< std::vector< ObjectWithDistance >, std::string > calculateClosestObjectToPose (const tf2_ros::Buffer &buffer, const std::vector< GraspableObject > &graspable_objects, const geometry_msgs::msg::PoseStamped &pose)
 
std::string getYAMLFileName ()
 
tl::expected< bool, std::string > isObjectSimilar (const tf2_ros::Buffer &buffer, const GraspableObject &input, const GraspableObject &reference, const std::string &base_frame, const double distance_threshold, const double orientation_threshold)
 
bool clientMustBeRecreated (const std::shared_ptr< rclcpp_action::ClientBase > &client, const std::string_view old_action_name, const std::string_view new_action_name)
 Compare an action client's current configuration to the desired new configuration to determine if the client needs to be recreated. More...
 
template<typename... Args>
std::optional< std::string > maybe_error (BT::Expected< Args >... args)
 Check if any of the provided inputs represent error states and, if so, return their error messages. More...
 
template<typename E , typename... Args>
constexpr std::optional< E > maybe_error (tl::expected< Args, E >... args)
 Tests if any of the expected args passed in has an error. More...
 
template<typename MessageT >
bool shouldRecreateSubscriber (const std::shared_ptr< rclcpp::Subscription< MessageT >> &subscriber, const std::string &topic_name, const rclcpp::QoS &publisher_qos)
 Compare a subscriber's current configuration to the desired new configuration to determine if the subscriber needs to be recreated. More...
 
tl::expected< rclcpp::TopicEndpointInfo, std::string > waitForPublisher (const std::shared_ptr< rclcpp::Node > &node, const std::string &topic_name)
 Waits for a publisher to be advertised on the provided topic, and gets the TopicEndpointInfo for the publisher once it appears. More...
 
template<typename T >
unwrapExpectedOrThrow (BT::Expected< T > exp)
 
template<typename... Args>
tl::expected< std::tuple< Args... >, std::string > getRequiredInputs (BT::Expected< Args >... args)
 
bool shouldRecreatePublisher (const std::shared_ptr< rclcpp::PublisherBase > &publisher, const std::string_view topic_name, const size_t queue_size, const rclcpp::ReliabilityPolicy reliability_policy)
 Compare a publisher's current configuration to the desired new configuration to determine if the publisher needs to be recreated. More...
 
bool clientMustBeRecreated (const std::shared_ptr< rclcpp::ClientBase > &client, const std::string_view new_service_name)
 Compare a service client's current configuration to the desired new configuration to determine if the client needs to be recreated. More...
 
template<typename T >
BT::NodeBuilder getDefaultNodeBuilder ()
 Helper function to create a BT::NodeBuilder for a behavior tree node with the default constructor signature. More...
 
template<typename T >
BT::NodeBuilder getSharedResourcesNodeBuilder (const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources)
 Helper function to create a BT::NodeBuilder for a behavior tree node which takes shared_ptr<BehaviorContext> as an additional constructor parameter. More...
 
template<typename T >
void registerBehavior (BT::BehaviorTreeFactory &factory, const std::string &name)
 Helper function to register a behavior with the default constructor signature with a BT::BehaviorTreeFactory. More...
 
template<typename T >
void registerBehavior (BT::BehaviorTreeFactory &factory, const std::string &name, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources)
 Helper function to register a behavior derived from SharedResourcesNode with a BT::BehaviorTreeFactory. More...
 

Variables

constexpr auto kClearOctomapServiceName = "clear_octomap"
 Constant service name used by the MoveIt ClearOctomap MoveGroup capability. More...
 
constexpr auto kDescriptionAddPoseStampedToVector
 
constexpr auto kDescriptionClearPoseStampedVector
 
constexpr auto kDescriptionPublishEmpty
 
constexpr auto kDescriptionPublishString
 
constexpr auto kDescriptionRegisterPointClouds
 
constexpr auto kDescriptionLoadFromYaml
 
constexpr auto kDescriptionLoadHeaderFromYaml = "<p>Loads a std::msg Header message from a YAML file.</p>"
 
constexpr auto kDescriptionLoadJointTrajectoryFromYaml
 
constexpr auto kDescriptionLoadObjectSubframeFromYaml
 
constexpr auto kDescriptionLoadPoseFromYaml = "<p>Loads a Pose message from a YAML file.</p>"
 
constexpr auto kDescriptionLoadPoseStampedFromYaml = "<p>Loads a PoseStamped message from a YAML file.</p>"
 
constexpr auto kDescriptionLoadPointStampedFromYaml = "<p>Loads a PointStamped message from a YAML file.</p>"
 
constexpr auto kDescriptionLoadQuaternionFromYaml = "<p>Loads a Quaternion message from a YAML file.</p>"
 
constexpr auto kDescriptionLoadVector3FromYaml = "<p>Loads a Vector3 message from a YAML file.</p>"
 
constexpr auto kDescriptionLoadTransformFromYaml = "<p>Loads a Transform message from a YAML file.</p>"
 
constexpr auto kDescriptionLoadTransformStampedFromYaml
 
constexpr auto kDescriptionLoadHeaderVectorFromYaml
 
constexpr auto kDescriptionLoadPoseVectorFromYaml = "<p>Loads a vector of Pose messages from a YAML file.</p>"
 
constexpr auto kDescriptionLoadPoseStampedVectorFromYaml
 
constexpr auto kDescriptionLoadPointStampedVectorFromYaml
 
constexpr auto kDescriptionLoadObjectSubframeVectorFromYaml
 
constexpr auto kDescriptionSaveToYaml
 
constexpr auto kDescriptionSaveHeaderToYaml
 
constexpr auto kDescriptionSaveJointTrajectoryToYaml
 
constexpr auto kDescriptionSavePoseToYaml
 
constexpr auto kDescriptionSavePoseStampedToYaml
 
constexpr auto kDescriptionSavePointStampedToYaml
 
constexpr auto kDescriptionSaveQuaternionToYaml
 
constexpr auto kDescriptionSaveVector3ToYaml
 
constexpr auto kDescriptionSaveTransformToYaml
 
constexpr auto kDescriptionSaveTransformStampedToYaml
 

Typedef Documentation

◆ AdjustPose

using moveit_studio::behaviors::AdjustPose = typedef moveit_studio_internal_msgs::srv::AdjustPose

◆ ApplyPlanningScene

typedef moveit_msgs::srv::ApplyPlanningScene moveit_studio::behaviors::ApplyPlanningScene

◆ AttachToolSrv

using moveit_studio::behaviors::AttachToolSrv = typedef moveit_studio_agent_msgs::srv::AttachTool

◆ CalibratePose

using moveit_studio::behaviors::CalibratePose = typedef robot_calibration_msgs::action::CalibratePose

◆ DetachToolSrv

using moveit_studio::behaviors::DetachToolSrv = typedef moveit_studio_agent_msgs::srv::DetachTool

◆ DoTeleoperate

using moveit_studio::behaviors::DoTeleoperate = typedef moveit_studio_sdk_msgs::action::DoTeleoperate

◆ ExecuteTaskSolution

using moveit_studio::behaviors::ExecuteTaskSolution = typedef moveit_task_constructor_msgs::action::ExecuteTaskSolution

◆ FollowJointTrajectory

using moveit_studio::behaviors::FollowJointTrajectory = typedef control_msgs::action::FollowJointTrajectory

◆ GetMasks2D

using moveit_studio::behaviors::GetMasks2D = typedef moveit_studio_vision_msgs::action::GetMasks2D

◆ GetPlanningScene

typedef moveit_msgs::srv::GetPlanningScene moveit_studio::behaviors::GetPlanningScene

◆ GripperCommand

using moveit_studio::behaviors::GripperCommand = typedef control_msgs::action::GripperCommand

◆ NavigateThroughPoses

using moveit_studio::behaviors::NavigateThroughPoses = typedef nav2_msgs::action::NavigateThroughPoses

◆ NavigateToPose

using moveit_studio::behaviors::NavigateToPose = typedef nav2_msgs::action::NavigateToPose

◆ RequestPointsFromUser

using moveit_studio::behaviors::RequestPointsFromUser = typedef moveit_studio_internal_msgs::srv::RequestPointsFromUser

◆ RequestTextFromUser

using moveit_studio::behaviors::RequestTextFromUser = typedef moveit_studio_internal_msgs::srv::RequestTextFromUser

◆ RetrieveBehaviorParameter

typedef moveit_studio_agent_msgs::srv::RetrieveBehaviorParameter moveit_studio::behaviors::RetrieveBehaviorParameter

◆ RetrieveJointState

using moveit_studio::behaviors::RetrieveJointState = typedef moveit_studio_agent_msgs::srv::RetrieveJointState

◆ RetrievePose

using moveit_studio::behaviors::RetrievePose = typedef moveit_studio_agent_msgs::srv::RetrievePose

◆ SendPointCloud2

using moveit_studio::behaviors::SendPointCloud2 = typedef moveit_studio_agent_msgs::srv::SendPointCloud2

◆ SetStringArray

using moveit_studio::behaviors::SetStringArray = typedef moveit_studio_agent_msgs::srv::SetStringArray

◆ ShapeCompletion

using moveit_studio::behaviors::ShapeCompletion = typedef moveit_studio_vision_msgs::action::ShapeCompletion

◆ StoreUidMap

using moveit_studio::behaviors::StoreUidMap = typedef moveit_studio_internal_msgs::srv::StoreUidMap

◆ SwitchPrimaryView

using moveit_studio::behaviors::SwitchPrimaryView = typedef moveit_studio_internal_msgs::srv::SwitchPrimaryView

◆ Trigger

using moveit_studio::behaviors::Trigger = typedef std_srvs::srv::Trigger

Function Documentation

◆ calculateClosestObjectToPose() [1/2]

tl::expected<std::vector<ObjectWithDistance>, std::string> moveit_studio::behaviors::calculateClosestObjectToPose ( const tf2_ros::Buffer &  buffer,
const std::vector< GraspableObject > &  graspable_objects,
const geometry_msgs::msg::PoseStamped &  pose 
)

◆ calculateClosestObjectToPose() [2/2]

tl::expected<std::vector<ObjectWithDistance>, std::string> moveit_studio::behaviors::calculateClosestObjectToPose ( const tf2_ros::Buffer &  buffer,
const std::vector< moveit_studio_vision_msgs::msg::GraspableObject > &  objects,
const geometry_msgs::msg::PoseStamped &  pose 
)

Get the closest object to the provided pose.

Parameters
objectsCollection of GraspableObjects to evaluate.
posePose to use for distance comparison.
Returns
If successful, returns a vector containing the input GraspableObjects sorted in ascending order by distance to the input pose. Returns a failure state if no qualifying object was found.

◆ clientMustBeRecreated() [1/2]

bool moveit_studio::behaviors::clientMustBeRecreated ( const std::shared_ptr< rclcpp::ClientBase > &  client,
const std::string_view  new_service_name 
)
inline

Compare a service client's current configuration to the desired new configuration to determine if the client needs to be recreated.

This checks two criteria:

  1. Is the client a nullptr? This will be the case the first time this Behavior is ticked in a new Objective, so the client must be created in that case.
  2. If the client already exists, does it communicate on a topic with the same name as the name provided through the input data port? If not, the client needs to be reinitialized to use the new topic.

This does NOT check if the client's QoS settings match the ones used by the server, because ServiceClientBehaviorBase always creates clients using the rmw_qos_profile_services_default QoS profile. Also, it is unlikely that a ROS 2 service server would use customized QoS settings.

Parameters
clientThe service client to check
new_service_nameThe new service name
Returns
True if the client must be recreated to satisfy the new configuration. False if the client's current configuration already satisfies the new configuration.

◆ clientMustBeRecreated() [2/2]

bool moveit_studio::behaviors::clientMustBeRecreated ( const std::shared_ptr< rclcpp_action::ClientBase > &  client,
const std::string_view  old_action_name,
const std::string_view  new_action_name 
)
inline

Compare an action client's current configuration to the desired new configuration to determine if the client needs to be recreated.

This checks two criteria:

  1. Is the client a nullptr? This will be the case the first time this Behavior is ticked in a new Objective, so the client must be created in that case.
  2. If the client already exists, does it communicate with an action with the same name as the name provided through the input data port? If not, the client needs to be reinitialized to use the new action name.

This does NOT check if the client's QoS settings match the ones used by the server, because ActionClientBehaviorBase always creates clients using the default ROS 2 action client QoS profile. It is also very complex to retrieve the QoS settings for an action server (since it's composed of a collection of services and topics). In any case action clients are almost always created with default QoS settings (or at the very least we've never seen one that used non-default settings).

Parameters
clientThe action client to check
new_action_nameThe new action name
Returns
True if the client must be recreated to satisfy the new configuration. False if the client's current configuration already satisfies the new configuration.

◆ createAddVirtualCollisionObjectToPlanningSceneRequest()

moveit_msgs::srv::ApplyPlanningScene::Request moveit_studio::behaviors::createAddVirtualCollisionObjectToPlanningSceneRequest ( const moveit_studio_vision_msgs::msg::GraspableObject &  graspable_object,
const moveit_msgs::msg::PlanningScene &  planning_scene 
)

Creates a ApplyPlanningScene::Request for adding a virtual collision object to the planning scene.

Parameters
graspable_objectThe virtual collision object to add to the planning scene
planning_sceneThe planning scene
Returns
Returns an appropriately created request.

◆ createRemoveCollisionObjectFromPlanningSceneRequest()

tl::expected< ApplyPlanningScene::Request, std::string > moveit_studio::behaviors::createRemoveCollisionObjectFromPlanningSceneRequest ( const std::string &  object_id,
moveit_msgs::msg::PlanningScene &  planning_scene 
)

◆ generateCoveragePath()

tl::expected< std::vector< Eigen::Isometry3d >, std::string > moveit_studio::behaviors::generateCoveragePath ( const Eigen::Isometry3d &  bottom_right_corner,
const double  width,
const double  height,
const double  stride_distance 
)

Generates a zig-zag path for a robot end-effector to follow, to cover a given area.

Parameters
bottom_right_cornerThe bottom right corner of the area to cover, with X pointing along the 'width' dimension and Y pointing along the 'height' dimension.
widthThe width of the area to cover.
heightThe height of the area to cover.
stride_distanceThe distance between strides in the coverage path.
Returns
A vector of poses that define the coverage path, or an error message.

◆ getDefaultNodeBuilder()

template<typename T >
BT::NodeBuilder moveit_studio::behaviors::getDefaultNodeBuilder ( )
inline

Helper function to create a BT::NodeBuilder for a behavior tree node with the default constructor signature.

Template Parameters
TCreate a builder for this type of node. Must be derived from BT::TreeNode.
Returns
A BT::NodeBuilder that creates a node of type T.

◆ getRequiredInputs()

template<typename... Args>
tl::expected<std::tuple<Args...>, std::string> moveit_studio::behaviors::getRequiredInputs ( BT::Expected< Args >...  args)
inline

Takes any number of BT::Expected (intended for use with the return of getInput()) and converts them to one larger tl::expected that contains a tuple of all their values to allow structured binding to all your Behavior's input variables at once.

◆ getSharedResourcesNodeBuilder()

template<typename T >
BT::NodeBuilder moveit_studio::behaviors::getSharedResourcesNodeBuilder ( const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &  shared_resources)
inline

Helper function to create a BT::NodeBuilder for a behavior tree node which takes shared_ptr<BehaviorContext> as an additional constructor parameter.

Parameters
shared_resourcesA shared_ptr to an instance of BehaviorContext, which will be provided when creating the behaviors registered by this function.
Template Parameters
TCreate a builder for this type of node. Must be derived from moveit_studio::behaviors::SharedResourcesNode.
Returns
A BT::NodeBuilder that creates a node of type T.

◆ getYAMLFileName()

std::string moveit_studio::behaviors::getYAMLFileName ( )

◆ isObjectSimilar() [1/2]

tl::expected<bool, std::string> moveit_studio::behaviors::isObjectSimilar ( const tf2_ros::Buffer &  buffer,
const GraspableObject &  input,
const GraspableObject &  reference,
const std::string &  base_frame,
const double  distance_threshold,
const double  orientation_threshold 
)

◆ isObjectSimilar() [2/2]

tl::expected<bool, std::string> moveit_studio::behaviors::isObjectSimilar ( const tf2_ros::Buffer &  buffer,
const moveit_studio_vision_msgs::msg::GraspableObject &  input,
const moveit_studio_vision_msgs::msg::GraspableObject &  reference,
const std::string &  base_frame,
const double  distance_threshold,
const double  orientation_threshold 
)

Helper function to check if two GraspableObjects are similar within some tolerance.

Parameters
bufferTF buffer, used to look up object poses relative to base_frame at the timestamp in the object header.
inputObject being compared. Must represent a single cuboid.
referenceObject being compared against. Must represent a single cuboid.
base_frameCommon fixed frame of reference between the two objects.
distance_thresholdObjects are considered dissimilar if their centroids are more than this distance away from each other.
orientation_thresholdObjects are considered dissimilar if the orientations of their centroids differ by this magnitude in radians.
Returns
If object similarity could be calculated without errors, returns true if the objects are similar and false if they are dissimilar. Returns an error message if the objects could not be compared successfully.

◆ maybe_error() [1/2]

template<typename... Args>
std::optional<std::string> moveit_studio::behaviors::maybe_error ( BT::Expected< Args >...  args)
inline

Check if any of the provided inputs represent error states and, if so, return their error messages.

This was inspired by fp's maybe_error function: https://github.com/tylerjw/fp/blob/b4bf17c2f7a99c07b6ab9b8706357572e960d638/include/fp/result.hpp#L216-L236

Parameters
argsOne or more BT::Expecteds (i.e., results from getInput)
Returns
std::optional wrapping std::string. If all of the inputs in args have values, returns std::nullopt. If one or more of the inputs in args contains an error state instead of a value, return a string that contains the concatenated error messages of all inputs that did not contain a value.

◆ maybe_error() [2/2]

template<typename E , typename... Args>
constexpr std::optional<E> moveit_studio::behaviors::maybe_error ( tl::expected< Args, E >...  args)
constexpr

Tests if any of the expected args passed in has an error.

This was adapted from fp's maybe_error function with a small modification.

Parameters
[in]Thetl::expected<T, E> variables. All have to use the same error type.
Template Parameters
EThe error type
ArgsThe value types for the tl::expected<T, E> args
Returns
The first error found or nothing

◆ registerBehavior() [1/2]

template<typename T >
void moveit_studio::behaviors::registerBehavior ( BT::BehaviorTreeFactory &  factory,
const std::string &  name 
)
inline

Helper function to register a behavior with the default constructor signature with a BT::BehaviorTreeFactory.

Parameters
factoryRegister behaviors with this factory.
nameThe name to use when registering this type of behavior. It is good practice to make this name match the name of the class (e.g., moveit_studio::behaviors::PlanMTCTask is registered as "PlanMTCTask").
Template Parameters
TRegister a behavior of this type.

◆ registerBehavior() [2/2]

template<typename T >
void moveit_studio::behaviors::registerBehavior ( BT::BehaviorTreeFactory &  factory,
const std::string &  name,
const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &  shared_resources 
)
inline

Helper function to register a behavior derived from SharedResourcesNode with a BT::BehaviorTreeFactory.

Parameters
factoryRegister behaviors with this factory.
nameThe name to use when registering this type of behavior. It is good practice to make this name match the name of the class (e.g., moveit_studio::behaviors::PlanMTCTask is registered as "PlanMTCTask").
shared_resourcesA shared_ptr to an instance of BehaviorContext, which will be provided when creating the behaviors registered by this function.
Template Parameters
TRegister a behavior of this type.

◆ requestSwitchCommandType()

tl::expected< void, std::string > moveit_studio::behaviors::requestSwitchCommandType ( std::shared_ptr< rclcpp::Client< moveit_msgs::srv::ServoCommandType >>  client,
std::shared_ptr< moveit_msgs::srv::ServoCommandType::Request >  request 
)

Send a request through a service client for a moveit_msgs::srv::ServoCommandType service and block until a response is received or a timeout limit is reached.

Parameters
clientService client to use
requestService request message to send
Returns
tl::expected containing void if the service succeeds. Returns an error string if the wait duration exceeded kServiceResponseMaxWait. Returns an error string if the server reports that the service request did not succeed.

◆ shouldRecreatePublisher()

bool moveit_studio::behaviors::shouldRecreatePublisher ( const std::shared_ptr< rclcpp::PublisherBase > &  publisher,
const std::string_view  topic_name,
const size_t  queue_size,
const rclcpp::ReliabilityPolicy  reliability_policy 
)
inline

Compare a publisher's current configuration to the desired new configuration to determine if the publisher needs to be recreated.

This checks two criteria:

  1. Is the publisher a nullptr? This will be the case the first time this Behavior is ticked in a new Objective, so the publisher must be created in that case.
  2. If the publisher already exists, does it publish to the right topic? If not, the publisher needs to be reinitialized to use the new topic name.
  3. If the publisher already exists, does its queue_size and reliability QoS settings match the new queue_size and reliability? If not, the publisher needs to be reinitialized with these new QoS settings.
Parameters
publisherThe existing publisher to check.
topic_nameThe topic name for the new configuration.
queue_sizeThe queue size for the new configuration.
reliability_policyThe reliability policy for the new configuration
Returns
True if the publisher must be recreated, and false if the publisher's current configuration already satisfies the new configuration.

◆ shouldRecreateSubscriber()

template<typename MessageT >
bool moveit_studio::behaviors::shouldRecreateSubscriber ( const std::shared_ptr< rclcpp::Subscription< MessageT >> &  subscriber,
const std::string &  topic_name,
const rclcpp::QoS &  publisher_qos 
)

Compare a subscriber's current configuration to the desired new configuration to determine if the subscriber needs to be recreated.

This checks three criteria:

  1. Is the subscriber a nullptr? This will be the case the first time this Behavior is ticked in a new Objective, so the subscriber must be created in that case.
  2. If the subscriber already exists, does it listen on the right topic? If not, the client needs to be reinitialized to use the new action name.
  3. If the subscriber already exists, does it use the same reliability QoS setting as the publisher? If not, the subscriber needs to be reinitialized using the same reliability QoS setting as the publisher.
Parameters
subscriberThe existing subscriber to check.
topic_nameThe topic name for the new configuration.
publisher_qosThe publisher's QoS for the new configuration.
Template Parameters
MessageTThe ROS message type used to specialize this function.
Returns
True if the subscriber must be recreated, and false if the subscriber's current configuration already satisfies the new configuration.

◆ splitSolutionAtIndex()

tl::expected< std::vector< moveit_task_constructor_msgs::msg::Solution >, std::string > moveit_studio::behaviors::splitSolutionAtIndex ( const moveit_task_constructor_msgs::msg::Solution  solution_in,
const std::size_t  index 
)

Split an MTC Solution message in two by dividing its vector of subtrajectories at the specified index.

The subtrajectory at the index will go into the second output MTC Solution. The task IDs of the new solutions will be set to match the task ID of the input solution.

The start_scene field of each new solution will be set to a new empty moveit_msgs::msg::PlanningScene message, since the MTC ExecuteSolution MoveGroup capability actually does not use this initial scene state when executing the solution. This is an implementation compromise – while a more thorough approach would be to calculate a new start_scene for the second half of the split soltuion by applying each scene diff from the subtrajectories in the first half of the split solution to the start_scene from the original solution, we would need to create an instance of a MoveIt PlanningScene object to do that, which introduces a lot of extra overhead like retrieving the robot model and SRDF.

The sub_solution field of each new solution will be set to an empty vector of moveit_task_constructor_msgs::msg::SubSolution messages. This is another implementation compromise – since MTC apparently does not need the subsolutions to execute each of the overall solution's subtrajectories, and there isn't a clear way to associate these subsolutions with a subset of the subtrajectories, we skip the step of copying subsolutions in to the halves of the split solution.

Parameters
solution_inInput MTC Solution message
indexThe index where the subtrajectories will be split.
Returns
A tl::expected wrapping a vector of MTC solutions. If there is no error, the vector will contain two MTC Solution messages, where the first one contains the portion of the input Solution that was before the split index and the second one contains the remainder of the solution. Returns an InvalidArgument error if the index would be out of range for the vector of subtrajectories.

◆ startServo()

tl::expected< void, std::string > moveit_studio::behaviors::startServo ( std::shared_ptr< rclcpp::Client< std_srvs::srv::SetBool >>  client)

Starts the servo node.

Returns
tl::expected containing void if validation succeeds. Returns an error message if the service call to start the servo server fails.

◆ stopServo()

tl::expected< void, std::string > moveit_studio::behaviors::stopServo ( std::shared_ptr< rclcpp::Client< std_srvs::srv::SetBool >>  client)

Stops the servo node.

Returns
tl::expected containing void if validation succeeds. Returns an error message if the service call to stop the servo server fails.

◆ unwrapExpectedOrThrow()

template<typename T >
T moveit_studio::behaviors::unwrapExpectedOrThrow ( BT::Expected< T >  exp)
inline

Attempts to unwrap a BT::Expected and throws an exception with a processed version of the error message from BT.CPP if there's no inner value.

◆ waitForPublisher()

tl::expected< rclcpp::TopicEndpointInfo, std::string > moveit_studio::behaviors::waitForPublisher ( const std::shared_ptr< rclcpp::Node > &  node,
const std::string &  topic_name 
)

Waits for a publisher to be advertised on the provided topic, and gets the TopicEndpointInfo for the publisher once it appears.

If multiple publishers are found on the same topic, this function just returns the TopicEndpointInfo for the first one in the order they were reported by the node. If multiple publishers advertise on the same topic with different reliability QoS settings the Behavior will only receive messages from the ones whose settings match the first publisher in the list. This situation will only happen if the publishers have been incorrectly configured, so this is not handled by this Behavior.

Parameters
nodeNode used to retrieve publisher info.
topic_nameName of the topic where we expect the publisher to advertise.
Returns
If one or more publishers were found on the topic, returns the TopicEndpointInfo for the first publisher that was found. If no publishers were found on the topic before the timeout elapsed, return an error result.

Variable Documentation

◆ kClearOctomapServiceName

constexpr auto moveit_studio::behaviors::kClearOctomapServiceName = "clear_octomap"
constexpr

Constant service name used by the MoveIt ClearOctomap MoveGroup capability.

◆ kDescriptionAddPoseStampedToVector

constexpr auto moveit_studio::behaviors::kDescriptionAddPoseStampedToVector
inlineconstexpr
Initial value:
= R"(
<p>
Adds a Cartesian pose to a sequence of Cartesian poses and stores the sequence to the blackboard.
</p>
)"

◆ kDescriptionClearPoseStampedVector

constexpr auto moveit_studio::behaviors::kDescriptionClearPoseStampedVector
inlineconstexpr
Initial value:
= R"(
<p>
Reset a vector containing PoseStamped messages.
</p>
)"

◆ kDescriptionLoadFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a vector of objects from a file, converts it and their names in the file to a vector of messages, and "
"writes that to an output data port.</p>"

◆ kDescriptionLoadHeaderFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadHeaderFromYaml = "<p>Loads a std::msg Header message from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionLoadHeaderVectorFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadHeaderVectorFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a vector of std::msg Header messages from a YAML file.</p>"

◆ kDescriptionLoadJointTrajectoryFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadJointTrajectoryFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a joint trajectory message from a YAML file name and outputs a JointTrajectory ROS message object "
"created from the file contents.</p>"

◆ kDescriptionLoadObjectSubframeFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadObjectSubframeFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a moveit_studio_vision_msgs::msg ObjectSubframe message from a YAML file.</p>"

◆ kDescriptionLoadObjectSubframeVectorFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadObjectSubframeVectorFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a vector of Subframes from a file, converts it and their names in the file to a vector of ROS "
"moveit_studio_vision_msgs::msg::ObjectSubframe messages, and writes that to an output data port.</p>"

◆ kDescriptionLoadPointStampedFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadPointStampedFromYaml = "<p>Loads a PointStamped message from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionLoadPointStampedVectorFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadPointStampedVectorFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a vector of PointStamped messages from a YAML file.</p>"

◆ kDescriptionLoadPoseFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadPoseFromYaml = "<p>Loads a Pose message from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionLoadPoseStampedFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadPoseStampedFromYaml = "<p>Loads a PoseStamped message from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionLoadPoseStampedVectorFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadPoseStampedVectorFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a vector of PoseStamped messages from a YAML file.</p>"

◆ kDescriptionLoadPoseVectorFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadPoseVectorFromYaml = "<p>Loads a vector of Pose messages from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionLoadQuaternionFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadQuaternionFromYaml = "<p>Loads a Quaternion message from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionLoadTransformFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadTransformFromYaml = "<p>Loads a Transform message from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionLoadTransformStampedFromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadTransformStampedFromYaml
inlineconstexpr
Initial value:
=
"<p>Loads a TransformStamped message from a YAML file.</p>"

◆ kDescriptionLoadVector3FromYaml

constexpr auto moveit_studio::behaviors::kDescriptionLoadVector3FromYaml = "<p>Loads a Vector3 message from a YAML file.</p>"
inlineconstexpr

◆ kDescriptionPublishEmpty

constexpr auto moveit_studio::behaviors::kDescriptionPublishEmpty
inlineconstexpr
Initial value:
= R"(
<p>
Publish a <code>std_msgs::msg::Empty</code> message to a topic.
</p>
)"

◆ kDescriptionPublishString

constexpr auto moveit_studio::behaviors::kDescriptionPublishString
inlineconstexpr
Initial value:
= R"(
<p>
Publish a <code>std_msgs::msg::String</code> message to a topic.
</p>
)"

◆ kDescriptionRegisterPointClouds

constexpr auto moveit_studio::behaviors::kDescriptionRegisterPointClouds
inlineconstexpr
Initial value:
= R"(
<p>
Finds the pose of a target point cloud relative to the base frame of a base point cloud using the Iterative Closest Point (ICP) algorithm.
</p>
)"

◆ kDescriptionSaveHeaderToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveHeaderToYaml
inlineconstexpr
Initial value:
=
"<p>Write a Header message given as a `std_msgs::msg::Header` message to a YAML file.</p>"

◆ kDescriptionSaveJointTrajectoryToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveJointTrajectoryToYaml
inlineconstexpr
Initial value:
=
"<p>Accepts a JointTrajectory ROS message object, a namespace, and a file name. Converts and saves the joint "
"trajectory message as a YAML file in the objectives directory at the provided file name and under the provided "
"namespace within the file.</p>"

◆ kDescriptionSavePointStampedToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSavePointStampedToYaml
inlineconstexpr
Initial value:
=
"<p>Write a point stamped given as a `geometry_msgs::msg::PoseStamped` message to a YAML file.</p>"

◆ kDescriptionSavePoseStampedToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSavePoseStampedToYaml
inlineconstexpr
Initial value:
=
"<p>Write a pose given as a `geometry_msgs::msg::PoseStamped` message to a YAML file.</p>"

◆ kDescriptionSavePoseToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSavePoseToYaml
inlineconstexpr
Initial value:
=
"<p>Write a pose given as a `geometry_msgs::msg::Pose` message to a YAML file.</p>"

◆ kDescriptionSaveQuaternionToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveQuaternionToYaml
inlineconstexpr
Initial value:
=
"<p>Write a Quaternion given as a `geometry_msgs::msg::Quaternion` message to a YAML file.</p>"

◆ kDescriptionSaveToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveToYaml
inlineconstexpr
Initial value:
=
"<p>Accepts a ROS message object, a namespace, and a file name. Converts and saves the message as a YAML file in "
"the Objectives directory at the provided file name and under the provided namespace within the file.</p>"

◆ kDescriptionSaveTransformStampedToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveTransformStampedToYaml
inlineconstexpr
Initial value:
=
"<p>Write a Transform given as a `geometry_msgs::msg::TransformStamped` message to a YAML file.</p>"

◆ kDescriptionSaveTransformToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveTransformToYaml
inlineconstexpr
Initial value:
=
"<p>Write a Transform given as a `geometry_msgs::msg::Transform` message to a YAML file.</p>"

◆ kDescriptionSaveVector3ToYaml

constexpr auto moveit_studio::behaviors::kDescriptionSaveVector3ToYaml
inlineconstexpr
Initial value:
=
"<p>Write a Vector3 given as a `geometry_msgs::msg::Vector3` message to a YAML file.</p>"