lbr_moveit

Warning

On hardware, do always execute in T1 mode first.

MoveIt Servo

MoveIt Servo - Simulation

  1. Run the mock setup (important to run the forward_position_controller controller for servoing):

    ros2 launch lbr_bringup mock.launch.py \
        ctrl:=forward_position_controller \
        model:=iiwa7 # [iiwa7, iiwa14, med7, med14]
    

    Hint

    For a physics-based simulation, also try Gazebo (remember to set mode:=gazebo for the next steps):

    ros2 launch lbr_bringup gazebo.launch.py \
        ctrl:=forward_position_controller \
        model:=iiwa7 # [iiwa7, iiwa14, med7, med14]
    
  2. Run MoveIt Servo:

    ros2 launch lbr_bringup moveit_servo.launch.py \
        mode:=mock \
        model:=iiwa7 # [iiwa7, iiwa14, med7, med14]
    
  3. Optionally run RViZ:

    ros2 launch lbr_bringup rviz.launch.py
    
  4. Publish to /lbr/servo_node/delta_joint_cmds and /lbr/servo_node/delta_twist_cmds. For this demo, we provide a keyboard driver (keyboard layout is printed to terminal):

    ros2 launch lbr_moveit keyboard_driver.launch.py
    

You can now experiment with

  • Modifying the MoveIt Servo parameters in moveit_servo.yaml. E.g. the robot_link_command_frame to change the commanding frame.

  • Connect a joystick or game controller.

  • Or changing the veloctiy scales for this keyboard driver in forward_keyboard.yaml.

MoveIt Servo - Hardware

  1. Client side configurations:

    1. Configure the client_command_mode to position in lbr_system_config.yaml

    2. Set the update_rate to 100 in hardware_controllers.yaml

  2. Remote side configurations:

    1. Select

      • FRI send period: 10 ms

      • IP address: your configuration

      • FRI control mode: POSITION_CONTROL or JOINT_IMPEDANCE_CONTROL

      • FRI client command mode: POSITION

  3. Proceed with steps 1, 2, 3 and 4 from MoveIt Servo - Simulation but with ros2 launch lbr_bringup hardware.launch.py in step 1.

MoveIt via RViz

MoveIt via RViz

IIWA 7 R800 in RViz

To run MoveIt via RViz, simply follow:

MoveIt via RViz - Simulation

  1. Run the mock setup:

    ros2 launch lbr_bringup mock.launch.py \
        model:=iiwa7 # [iiwa7, iiwa14, med7, med14]
    

    Hint

    For a physics-based simulation, also try Gazebo (remember to set mode:=gazebo for the next steps):

    ros2 launch lbr_bringup gazebo.launch.py \
        model:=iiwa7 # [iiwa7, iiwa14, med7, med14]
    
  2. Run MoveIt with RViz:

    ros2 launch lbr_bringup move_group.launch.py \
        mode:=mock \
        rviz:=true \
        model:=iiwa7 # [iiwa7, iiwa14, med7, med14]
    
  3. You can now move the robot via MoveIt in RViz!

MoveIt via RViz - Hardware

  1. Client side configurations:

    1. Configure the client_command_mode to position in lbr_system_config.yaml

    2. Set the update_rate to 100 in hardware_controllers.yaml

  2. Remote side configurations:

    1. Select

      • FRI send period: 10 ms

      • IP address: your configuration

      • FRI control mode: POSITION_CONTROL or JOINT_IMPEDANCE_CONTROL

      • FRI client command mode: POSITION

  3. Proceed with steps 1 and 2 from MoveIt via RViz - Simulation but with ros2 launch lbr_bringup hardware.launch.py in step 1.