xArm-Developer / xarm_ros2

ROS2 developer packages for robotic products from UFACTORY
https://www.ufactory.cc/pages/xarm
BSD 3-Clause "New" or "Revised" License
115 stars 72 forks source link

How to use the xarm package without moveit wrappers #64

Closed gaspatxo closed 6 months ago

gaspatxo commented 6 months ago

Hi, we are on the process of developing a ros package that is meant to be usable with any moveit2 enabled robot arm. As hardware we have an xArm7 and would like to both interact with simulations and the real hardware using moveit's standard interface.

Our current goal is to simply to push a goal pose using Moveit's Move group script.

The current node we are trying to run is the following:

#include <memory>

#include <rclcpp/rclcpp.hpp>
#include <moveit/move_group_interface/move_group_interface.h>

int main(int argc, char *argv[])
{
  auto node_name = "arm_controller";
  // Initialize ROS and create the Node
  rclcpp::init(argc, argv);
  auto const node = std::make_shared<rclcpp::Node>(
      node_name,
      rclcpp::NodeOptions().automatically_declare_parameters_from_overrides(true));

  // Create a ROS logger
  auto const logger = rclcpp::get_logger(node_name);

  RCLCPP_INFO(logger, "node started...");

  // Create the MoveIt MoveGroup Interface
  using moveit::planning_interface::MoveGroupInterface;
  auto move_group_interface = MoveGroupInterface(node, "xarm7");

  RCLCPP_INFO(logger, "created MoveGroupInterface");

  // Set a target Pose
  auto const target_pose = []
  {
    geometry_msgs::msg::Pose msg;
    msg.orientation.w = 1.0;
    msg.position.x = 0.28;
    msg.position.y = -0.2;
    msg.position.z = 0.5;
    return msg;
  }();
  move_group_interface.setPoseTarget(target_pose);

  // Create a plan to that target pose
  auto const [success, plan] = [&move_group_interface]
  {
    moveit::planning_interface::MoveGroupInterface::Plan msg;
    auto const ok = static_cast<bool>(move_group_interface.plan(msg));
    return std::make_pair(ok, msg);
  }();

  // Execute the plan
  if (success)
    move_group_interface.execute(plan);
  else
    RCLCPP_ERROR(logger, "Planing failed!");

  // Shutdown ROS
  rclcpp::shutdown();
  return 0;
}

The first thing we tried was launching the xarm_moveit_config package with

ros2 launch xarm_moveit_config xarm7_moveit_fake.launch.py

And then running the node with ros2 run <our npackage> <our_node>. This would not work because the xarm package does not publish /robot_description_semantic which contains the .srdf file. We see that currently xarm_ros2 passes that as a parameter during the launch process.

Then, after reading a bit about launching Moveit Configuration. We using the following .launch.py file:

import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from ament_index_python.packages import get_package_share_directory
from moveit_configs_utils import MoveItConfigsBuilder

def generate_launch_description():

    # Define xacro mappings for the robot description file
    launch_arguments = {
        # "robot_ip": "xxx.yyy.zzz.www",
        # "use_fake_hardware": "true",
        # "gripper": "robotiq_2f_85",
        # "dof": "7",
    }

    # Load the robot configurationl
    moveit_config = (
        MoveItConfigsBuilder("xarm7", package_name="xarm_moveit_config")
        .robot_description(
            file_path="urdf/xarm7/xarm7.urdf.xacro",
            mappings=launch_arguments,
        )
        .trajectory_execution(file_path="config/xarm7/fake_controllers.yaml")
        .planning_scene_monitor(
            publish_robot_description=True, publish_robot_description_semantic=True
        )
        .planning_pipelines(
            pipelines=["ompl", "stomp", "pilz_industrial_motion_planner"]
        )
        .to_moveit_configs()
    )

    # Start the actual move_group node/action server
    run_move_group_node = Node(
        package="our_package",
        executable="arm_controller",
        output="screen",
        parameters=[moveit_config.to_dict()],
    )

    return LaunchDescription(
        [
            run_move_group_node,
        ]
    )

However, MoveItConfigsBuilder is unable to interpret the xarm_moveit_config package.

WARNING:root:Cannot infer URDF from `/home/redacted/Lab/raven/raven_ws/install/xarm_moveit_config/share/xarm_moveit_config`. -- using config/xarm7.urdf
WARNING:root:Cannot infer SRDF from `/home/redacted/Lab/raven/raven_ws/install/xarm_moveit_config/share/xarm_moveit_config`. -- using config/xarm7.srdf
[ERROR] [launch]: Caught exception in launch (see debug for traceback): Caught multiple exceptions when trying to load file of format [py]:
 - ParameterBuilderFileNotFoundError: "File /home/redacted/Lab/raven/raven_ws/install/moveit_configs_utils/share/moveit_configs_utils/default_configs/stomp_planning.yaml doesn't exist"
 - InvalidFrontendLaunchFileError: The launch file may have a syntax error, or its format is unknown

In look for alternatives, we then tried using moveit_setup_assistant, feeding it the .urdf generated and published in /robot_description. Which would lead to the computer freezing and needing a reboot in order to get it back to work.

In short, we would like to use xarm7 both in sim and in real life by means of the cpp moveit move_group interface and we do not know how. We are not experienced with moveit and would really appreciate your help. Thank you.

gaspatxo commented 6 months ago

Hi, we found a way to get this, we are basically using the same launch file as in xarm_planner -> _robot_planner.launch.py to launch our node. Whilst we setup the rviz simulation with ros2 launch xarm_moveit_config _robot_moveit_fake.launch.py no_gui_ctrl:=true.

With this then we can use moveit_group in our node without a problem.

I understand that this issues is related to the lack of compatibility with MoveItConfigsBuilder

Still, we are left in doubt on wether this is the best or meant way to do things. Any help or advice would be appreciated.

penglongxiang commented 6 months ago

Hi @gaspatxo, our moveit_config packages are not automatically generated by moveit setup assistant, and our xarm_moveit_config package does not obey the naming rule for MoveitConfigsBuilder inferring, since the package for xarm7 should have the name xarm7_moveit_config. We designed our packages to present a more compact structure, because we have many robot models, if each model would have one moveit pakage, then "xarm_ros2" would appear to be bulky and full of redundant similar files (like our ROS1 repository).

For the above reason, most of our launch and configuration files are hand-edited instead of automatically generated, which may result in difficulties for MoveitConfigsBuilder analyzing. So I am afraid you may have to do additional work in order to fit xarm7 into a generalized software structure. I wonder if making a new (fake) xarm7_moveit_config package for MoveitConfigsBuilder while overwriting the default files in initialization with the real .srdf and .urdf files etc would work.

I am also glad that you have already found a way around. xarm_planner package is the one we use for move_group interface coding control. Since it will not be easy to transfer the structure of this repo to be compatible with MoveitConfigsBuilder, I guess you can continue going this way if it is OK for your application.

gaspatxo commented 6 months ago

Thank you for your reply @penglongxiang . I will then keep using the mentioned solution.

Still, I cannot help but wonder. One of the great feature of ROS is that it is hardware agnostic, and that one only has to learn moveit in order to make us of any ros-enabled arm. Therfore my question is: why make a wrapper and a product-specific API when making your products ROS-compatible; it seems to me like missing a large part of the ROS point, and also an avoidable load on developement which has already been done by Moveit2.

I would like to encourage the creation of much simpler repos for each product of yours which developers can simply download, feed to MoveitConfigsBuilder and control via their preferred standard Moveit API.

penglongxiang commented 6 months ago

Hi @gaspatxo, thanks for your feedback. We started the development of ros2 support early, and by that time, there is no MoveitConfigsBuilder available and we could not foresee the way it interprets the package, which requires naming convention. We did the naming change to make the structure less redundant. After starting the launch files according to the ReadMe file, our package will still work in ROS2 eco-system with other ros2 enabled devices.

However, I agree with your point here. We will do some more thoughts to see if there is a better way to support MoveitConfigsBuilder and robot-agnostic development.

gaspatxo commented 6 months ago

Just for completion. If you want to use your UFactory robot with the standard moveit API, here is a way to do it (mind that this is for humble, it probably works with any other ros2 branch but I do not guarantee it):

  1. Copy _robot_planner.launch.py to the launch directory in your package
  2. Optionally, though convenient, set the right default parameters for your hardware (this will spare you from specifying it in your ros2 launch command). In case of doubt you can check files such as uf850_planner_fake.launch.py
  3. Delete the xarm_gripper_planner_node launcher:
    if add_gripper.perform(context) in ('True', 'true') and use_gripper_node.perform(context) in ('True', 'true'):
        xarm_gripper_planner_node = Node(
            name=node_name,
            package='xarm_planner',
            executable='xarm_gripper_planner_node',
            output='screen',
            parameters=[
                robot_description_parameters,
                {'PLANNING_GROUP': 'xarm_gripper'},
            ],
        )
        nodes.append(xarm_gripper_planner_node)
  1. Modify the xarm_planner_node parameters to launch your executable:

line 32:

    node_executable = LaunchConfiguration('node_executable', default='<YOUR_EXECUTABLE>')

line 120:

    xarm_planner_node = Node(
        name=node_name,
        package='<YOUR_PACKAGE>',
        executable=node_executable,
        output='screen',
        parameters=[
            robot_description_parameters,
            {
                'robot_type': robot_type,
                'dof': dof
            },
            xarm_planner_parameters,
        ],
    )
penglongxiang commented 5 months ago

Hi @gaspatxo, we have developed a customized version of MoveitConfigsBuilder, which has similar interface with the official one and some additional arguments to adapt to our package. Please refer to the instruction here and see if this can better help your application.

Shahar-AstroScale commented 2 weeks ago

Hi, we found a way to get this, we are basically using the same launch file as in xarm_planner -> _robot_planner.launch.py to launch our node. Whilst we setup the rviz simulation with ros2 launch xarm_moveit_config _robot_moveit_fake.launch.py no_gui_ctrl:=true.

With this then we can use moveit_group in our node without a problem.

I understand that this issues is related to the lack of compatibility with MoveItConfigsBuilder

Still, we are left in doubt on wether this is the best or meant way to do things. Any help or advice would be appreciated.

Hey i had encountered the same problem, i am trying to use c++ binding, hello_moveit.cpp on uf850, can you guide me through the solution? thanks