Skip to content

Latest commit

 

History

History
107 lines (96 loc) · 4.82 KB

readme.md

File metadata and controls

107 lines (96 loc) · 4.82 KB

This is a demo connecting the chassis and xarm6

Mainly to demonstrate how to build and drive the xarm and chassis together. Here, mbot is used instead of chassis.

URDF

  • urdf/mbot_with_xarm.urdf.xacro
    • Define the parameters required by the xarm urdf and pass them to the xarm urdf (see the parameters of the xarm urdf)

      • xarm urdf: xarm_description/urdf/xarm_device_macro.xacro
      • Note: Please set the values ​​of some parameters according to the actual situation
        • In the demo, set the parameter attach_to to the "base_link" of the mbot and modify the offset attach_xyz
    • Define the parameters required for mbot urdf and pass them to mbot urdf (see mbot urdf for parameters)

      • mbot urdf: urdf/mbot_macro.xacro
        • urdf/mbot.urdf.xacro
        • urdf/mbot.transmission.xacro
        • urdf/mbot.ros2_control.xacro
        • urdf/mbot.gazebo.xacro
      • Note: The demo only defines and passes the parameter ros2_control_plugin

SRDF

  • mbot_with_xarm.srdf.xacro
    • Define the parameters required by the xarm srdf and pass them to the xarm srdf (see the parameters of the xarm srdf)
      • xarm srdf: xarm_moveit_config/srdf/xarm_macro.srdf.xacro
    • Define the parameters required by mbot srdf and pass them to mbot srdf (see mbot srdf for parameters)
      • mbot srdf: srdf/mbot_macro.srdf.xacro
      • Note: The demo only defines and passes the prefix parameter

ros2_control config

  • config/ros2_controllers.yaml: Contains xarm and mbot configuration
    • Note: You can copy the corresponding xarm configuration from xarm_controller/config and then add the mbot configuration

moveit config

  • config/controllers.yaml
  • config/joint_limits.yaml
  • config/kinematics.yaml
  • config/ompl_planning.yaml
    • You can copy the corresponding xarm configuration from xarm_moveit_config/config and then add the mbot configuration
    • The demo does not add any mbot configuration.

rviz config

  • rviv/moveit.rviz
  • Note
    • Demo is just copied from xarm_moveit_config/rviz/moveit.rviz and the "Fixed Frame" is modified to be the "base_footprint" link of the mbot

gazebo world file

  • worlds/empty.world

launch file

  • launch/mbot_moveit_fake.launch.py

  • launch/mbot_moveit_gazebo.launch.py

    • launch/_robot_on_mbot_gazebo.launch.py
  • launch/mbot_moveit_realmove.launch.py

  • Note

    • When generating ros2_control parameters, specify the use of the config/ros2_controller.yalm file
      ros2_control_params = generate_ros2_control_params_temp_file(
          os.path.join(get_package_share_directory('mbot_demo'), 'config', 'ros2_controllers.yaml'),
          prefix=prefix.perform(context), 
          add_gripper=add_gripper.perform(context) in ('True', 'true'),
          add_bio_gripper=add_bio_gripper.perform(context) in ('True', 'true'),
          ros_namespace=ros_namespace,
          robot_type=robot_type.perform(context)
      )
    • ros2_control_plugin parameters are set according to actual conditions
      • uf_robot_hardware/UFRobotFakeSystemHardware: only for fake
      • uf_robot_hardware/UFRobotSystemHardware: only for xarm real machine
      • gazebo_ros2_control/GazeboSystem: only for gazebo
    • Specify the file path when generating moveit_config
      pkg_path = os.path.join(get_package_share_directory('mbot_demo'))
      urdf_file = os.path.join(pkg_path, 'urdf', 'mbot_with_xarm.urdf.xacro')
      srdf_file = os.path.join(pkg_path, 'srdf', 'mbot_with_xarm.srdf.xacro')
      
      controllers_file = os.path.join(pkg_path, 'config', 'controllers.yaml')
      joint_limits_file = os.path.join(pkg_path, 'config', 'joint_limits.yaml')
      kinematics_file = os.path.join(pkg_path, 'config', 'kinematics.yaml')
      pipeline_filedir = os.path.join(pkg_path, 'config')
      
      # demo for fake
      moveit_config = (
          MoveItConfigsBuilder(
              context=context,
              dof=dof,
              robot_type=robot_type,
              prefix=prefix,
              limited=limited,
              attach_to=attach_to,
              attach_xyz=attach_xyz,
              attach_rpy=attach_rpy,
              ros2_control_plugin=ros2_control_plugin,
              ros2_control_params=ros2_control_params,
              add_gripper=add_gripper,
              add_vacuum_gripper=add_vacuum_gripper,
              add_bio_gripper=add_bio_gripper,
          )
          .robot_description(file_path=urdf_file) # urdf path
          .robot_description_semantic(file_path=srdf_file) # srdf path
          .robot_description_kinematics(file_path=kinematics_file) # kinematics path
          .joint_limits(file_path=joint_limits_file) # joint_limits path
          .trajectory_execution(file_path=controllers_file) # controllers path
          .planning_pipelines(config_folder=pipeline_filedir) # planning pipeline config directory
          .to_moveit_configs()
      )