Hello everyone!
Since the first topic is quite clogged up with obsolete technical details, I’m creating a new one with more detailed and practical information on why I created ManyMove, what features it has and how it works.
WHY
- ManyMove is a simple robot manipulation framework for ROS2, leveraging some popular packages like MoveIt2 and Behavior Trees. It aims to help roboticists transition from proprietary robot programming languages and frameworks to ROS by .
- Depending on the application’s complexity, every time a roboticist starts using a new robot brand it needs weeks or months just to learn all the new sintax, the programming interface, the auxiliary functionalities for I/O mapping, and so on. For complex projects that require advanced functionalities and fine control on critical motion detail, this is basically unavoidable. But for simple projects it raises an entry barrier for roboticists that want to transition to another brand.
- ROS can help tear down this barrier, but it still requires a steep learning curve even to develop a simple application. ManyMove provides functioning templates for end-to-end real-world applications, and in particular simple manipulation applications with cobots and industrial robots, either single or dual robot.
I started creating ManyMove because I needed some basic functionalities for my applications that don’t seem to be implemented in the standard packages.
Please note that the functionalities listed below and their implementation are not meant to represent “how it should be done”: it’s just something that I implemented as I could to obtain a functioning solution for my needs. There’s a lot of room for improvement, and any suggestion or contribution is welcome!
WHAT
- Cartesian speed limit for all types of moves, regardless of the motion planning pipeline used. This lets you stay within the mandatory cartesian speed limits for cobots without having to tune down too much velocity and acceleration scaling, boosting cycle times.
- Soft Stop: an abrupt stop motion behavior is never desirable in a real industrial setup, unless it’s an emergency situation. Here I implemented a soft stop using a simple one-point trajectory with a
time_from_start
parameter, which generates a spring-back motion to the robot’s position at the moment the stop command is triggered. - Re-using previously successfull trajectories: some planning pipelines are very powerful but slow to compute, or fairly fast but not as predictable (or not as versatile). When a trajectory is successfully executed, ManyMove stores it so it can be reused withouth creating a new one: perfect to get optimal trajectories and reduced cycle tymes on complex scenarios with repetitive tasks. If you don’t like a trajectory, you just have to hit the stop button while it executes and then start again: since it failed, it will plan it again from scratch on next cycle iteration.
- Real time collision check on all trajectories: enables working with multiple robots on the scene and in dynamic environments, while still using the basic Moveit2 functionalities.
- Robot-brand agnostic: you just need a functioning moveit config for your robot to load it up on ManyMove. The templates/examples include scenarios of increased complexity: from single robot with a pneumatic or actuated gripper and a basic interface, to dual robot configuration, dynamic interaction between the two robots and a more complete HMI.
- Logic built on Behavior Trees: it eases the construction of complex logic cycles. All the logic is built programmatically, and can be checked at runtime on the tree visualizer.
- Simple HMI dinamically interacting with the Behavior Tree through ROS2 services.
HOW
If you want to create a new application in ManyMove, once you have a working moveit config package you just need the following information:
- Base frame/link of the robot
- TCP (end effector) frame/link
- traj_controller action server name
- Robot’s name/model
- Planner type: choose between moveitcpp or movegroup
When using an actuated gripper you also need:
- The name of the action server to control the gripper
- The list of the gripper’s links to exclude from collision checking
When using multiple robots with a single URFD, you’ll need a prefix for each robot (see the dual_* examples).
These values will be used to start up the following nodes:
- action_server_node: the core of the planners
- manymove_py_trees_node: the BT logic node
- manymove_hmi_node: the HMI interface
- manymove_signals: on a real robot, handles the service calls to get/set signals (currently taylored for Ufactory robots)
A little side note: the reference TCP frame here is not actually centered between gripper’s fingers, as ‘panda_link8’ represents the center of the flange. But since it’s aligned to the ideal TCP, you can just offset the poses when you need to refer to the TCP, without having to create a new link. For example, the -0.102 in the following line represents this offset:
blackboard->set("pick_pre_transform_xyz_rpy_1_key", std::vector<double>{-0.102, 0.0, 0.0, 0.0, 1.57, 0.0});
Right now the most extensive executable examples are found in manymove_cpp_trees repo: you can start from one of the bt_* executables there, taking care to use valid joint targets and poses for your robot. Also take some time setting up move.hpp coherently with the speed limits of your robot and planning pipeline of your choice.
When you go through the code, you’ll notice I explain what each section does and how to use it: I tried to keep it updated while modifying the repo, but some comments may be outdated or not relevant anymore. Please let me know if something is not clear!
An example of application with two robots interacting:
Also consider that the huge behavior tree shown in the picture can be summed up in code with this snippet:
// General startup/reset sequence:
std::string startup_sequence_xml = sequenceWrapperXML(
"StartUpSequence",
{
spawn_fixed_objects_xml,
reset_movable_objects_xml,
reset_graspable_objects_xml,
parallel_sub_startup_sequences_xml,
});
// ROBOT 1
// Repeat node must have only one children, so it also wraps a Sequence child that wraps the other children
std::string repeat_forever_wrapper_1_xml = repeatSequenceWrapperXML(
"RepeatForever",
{
go_to_ready_pose_1_xml, //< Go to ready position
set_robot_1_out_of_working_position, //< Signal robot 1 out of working position
wait_for_cycle_on, //< Wait for robot cycle to be on
spawn_graspable_object_1_xml, //< Add the graspable object to the scene
reset_movable_objects_xml, //< Reset and reload the movable objects in the scene
get_grasp_object_poses_1_xml, //< Get the updated poses relative to the graspable object
go_to_pick_pose_1_xml, //< Pick move sequence
close_gripper_1_xml, //< Attach the object
go_to_wait_pose_1_xml, //< Go to wait pose
wait_for_robot_2_out_of_working_position_xml, //< Wait for other robot out of working position
wait_for_renamed_obj_removed_xml, //< Wait for other robot to unload the graspable object
go_to_drop_pose_1_xml, //< Drop move sequence
set_robot_1_in_working_position_xml, //< Signal robot 1 in working position
wait_for_robot_2_in_working_position_xml, //< Wait for other robot to be in working position
open_gripper_1_xml, //< Detach the object
rename_obj_1_xml, //< Rename the object for the other robot to use
},
-1); //< num_cycles=-1 for infinite
// ROBOT 2
// Repeat node must have only one children, so it also wraps a Sequence child that wraps the other children
std::string repeat_forever_wrapper_2_xml = repeatSequenceWrapperXML(
"RepeatForever",
{
go_to_ready_pose_2_xml, //< Go to ready position
set_robot_2_out_of_working_position_xml, //< Signal robot 2 out of working position
wait_for_robot_1_in_working_position_xml, //< Wait for other robot in working position
get_grasp_object_poses_2_xml, //< Get the updated poses relative to the renamed graspable object
get_load_poses_from_endplate_xml, //< Get the updated pose from the machine's end plate
go_to_insert_pose_2_xml, //< Go to insert pose
set_robot_2_in_working_position, //< Signal robot 2 in working position
wait_for_robot_1_out_of_working_position_xml, //< Wait for other robot out of working position
wait_for_renamed_drop_obj_xml, //< Wait for other robot to release the graspable object and rename it
attach_obj_2_xml, //< Attach the renamed graspable object
go_to_load_pose_2_xml, //< Load sequence
go_to_exit_pose_2_xml, //< Exit sequence
detach_obj_2_xml, //< Detach the object
remove_obj_2_xml, //< Delete the object for it to be added on the next cycle in the original position
},
-1); //< num_cycles=-1 for infinite
// Runningh both robot sequences in parallel:
std::string parallel_repeat_forever_sequences_xml = parallelWrapperXML("PARALLEL_MOTION_SEQUENCES", {repeat_forever_wrapper_1_xml, repeat_forever_wrapper_2_xml}, 2, 1);
std::string retry_forever_wrapper_xml = retrySequenceWrapperXML("RetryForever", {startup_sequence_xml, parallel_repeat_forever_sequences_xml}, -1);
// MasterSequence with startup sequence and RepeatForever as child to set BehaviorTree ID and root main_tree_to_execute in the XML
std::vector<std::string> master_branches_xml = {retry_forever_wrapper_xml};
std::string master_body = sequenceWrapperXML("GlobalMasterSequence", master_branches_xml);