Turtlebot3教程|JTDQ logo Turtlebot3教程|JTDQ

Manipulation

NOTE:

  • This instructions were tested on Ubuntu 16.04 and ROS Kinetic Kame.
  • If you want more specfic information about OpenMANIPULATOR, please refer to the OpenMANIPULATOR e-Manual.

TIP: The terminal application can be found with the Ubuntu search icon on the top left corner of the screen. The shortcut key for running the terminal is Ctrl-Alt-T.

TurtleBot3 with OpenMANIPULATOR

The OpenMANIPULATOR by ROBOTIS is one of the manipulators that support ROS, and has the advantage of being able to easily manufacture at a low cost by using Dynamixel actuators with 3D printed parts.

The OpenMANIPULATOR has the advantage of being compatible with TurtleBot3 Waffle and Waffle Pi. Through this compatibility can compensate for the lack of freedom and can have greater completeness as a service robot with the the SLAM and Navigation capabilities that the TurtleBot3 has. TurtleBot3 and OpenMANIPULATOR can be used as a mobile manipulator and can do things like the following videos.

Software Setup

NOTE: Before you install open_manipulator_with_tb3 packages, please make sure turtlebot3 and open_manipulator packages have been installed previously in RemotePC and setup Raspberry Pi 3.

[Remote PC]

$ cd ~/catkin_ws/src/
$ git clone https://github.com/ROBOTIS-GIT/open_manipulator_with_tb3.git
$ git clone https://github.com/ROBOTIS-GIT/open_manipulator_with_tb3_msgs.git
$ git clone https://github.com/ROBOTIS-GIT/open_manipulator_with_tb3_simulations.git
$ git clone https://github.com/ROBOTIS-GIT/open_manipulator_perceptions.git
$ sudo apt-get install ros-kinetic-smach* ros-kinetic-ar-track-alvar ros-kinetic-ar-track-alvar-msgs
$ cd ~/catkin_ws && catkin_make

TIP: Before executing this command, you have to specify the model name of TurtleBot3. The ${TB3_MODEL} is the name of the model you are using in waffle, waffle_pi. If you want to permanently set the export settings, please refer to Export TURTLEBOT3_MODEL page.

[RemotePC]

$ export TURTLEBOT3_MODEL=${TB3_MODEL}
$ roslaunch open_manipulator_with_tb3_description open_manipulator_with_tb3_rviz.launch

Hardware Setup

OpenCR Setup

NOTE: You can choose one of methods for uploading firmware. But we highly recommend to use shell script. If you need to modify TurtleBot3’s firmware, you can use the second method.

  • Method #1: Shell Script, upload the pre-built binary file using the shell script.
  • Method #2: Arduino IDE, build the provided source code and upload the generated binary file using the Arduino IDE.

Shell Script

[TurtleBot3]

$ export OPENCR_PORT=/dev/ttyACM0
$ export OPENCR_MODEL=om_with_tb3
$ rm -rf ./opencr_update.tar.bz2
$ wget https://github.com/ROBOTIS-GIT/OpenCR-Binaries/raw/master/turtlebot3/ROS1/latest/opencr_update.tar.bz2 && tar -xvf opencr_update.tar.bz2 && cd ./opencr_update && ./update.sh $OPENCR_PORT $OPENCR_MODEL.opencr && cd ..

When firmware upload is completed, jump_to_fw text string will be printed on the terminal.

Arduino IDE

[Remote PC]

NOTE: If error occurs while uploading firmware, go to ToolsPort and check if correct port is selected. Press Reset button on the OpenCR and try to upload the firmware again.

TIP: The Dynamixel ids can be changed in open_manipulator_driver.h in turtlebot3_with_open_manipulator folder

Bringup

NOTE: Please double check the OpenCR usb port name in turtlebot3_core.launch

TIP: Before executing this command, you have to specify the model name of TurtleBot3. The ${TB3_MODEL} is the name of the model you are using in waffle, waffle_pi. If you want to permanently set the export settings, please refer to Export TURTLEBOT3_MODEL page.

[TurtleBot3] Launch rosserial and lidar node

$ export TURTLEBOT3_MODEL=${TB3_MODEL}
$ ROS_NAMESPACE=om_with_tb3 roslaunch turtlebot3_bringup turtlebot3_robot.launch multi_robot_name:=om_with_tb3 set_lidar_frame_id:=om_with_tb3/base_scan

[TurtleBot3] Launch rpicamera node

$ ROS_NAMESPACE=om_with_tb3 roslaunch turtlebot3_bringup turtlebot3_rpicamera.launch

[Remote PC] Launch Launch robot_state_publisher node

$ ROS_NAMESPACE=om_with_tb3 roslaunch open_manipulator_with_tb3_tools om_with_tb3_robot.launch

SLAM

[Remote PC] Launch slam node

$ export TURTLEBOT3_MODEL=${TB3_MODEL}
$ roslaunch open_manipulator_with_tb3_tools slam.launch use_platform:=true

[Remote PC] Launch teleop node

$ ROS_NAMESPACE=om_with_tb3 roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch

[Remote PC] Launch map_saver node

$ ROS_NAMESPACE=om_with_tb3 rosrun map_server map_saver -f ~/map

$ export TURTLEBOT3_MODEL=${TB3_MODEL}
$ roslaunch open_manipulator_with_tb3_tools navigation.launch use_platform:=true

MoveIt!

$ rosservice call /arm/moveit/get_joint_position "planning_group: 'arm'" 
joint_position: 
  joint_name: [joint1, joint2, joint3, joint4]
  position: [-0.003067961661145091, -0.42644667625427246, 1.3084856271743774, -0.8452234268188477]
  max_accelerations_scaling_factor: 0.0
  max_velocity_scaling_factor: 0.0
$ rosservice call /arm/moveit/get_kinematics_pose "planning_group: 'arm'
end_effector_name: ''" 
header: 
  seq: 0
  stamp: 
    secs: 1550714737
    nsecs: 317547871
  frame_id: "/base_footprint"
kinematics_pose: 
  pose: 
    position: 
      x: 0.0918695085861
      y: -0.000263644738325
      z: 0.218597669468
    orientation: 
      x: 1.82347658316e-05
      y: 0.023774433021
      z: -0.000766773548775
      w: 0.999717054001
  max_accelerations_scaling_factor: 0.0
  max_velocity_scaling_factor: 0.0
  tolerance: 0.0
$ rosservice call /om_with_tb3/gripper "planning_group: ''
joint_position:
  joint_name:
  - ''
  position:
  - 0.15
  max_accelerations_scaling_factor: 0.0
  max_velocity_scaling_factor: 0.0
path_time: 0.0"

Simulation

$ export TURTLEBOT3_MODEL=${TB3_MODEL}
$ roslaunch open_manipulator_with_tb3_gazebo empty_world.launch

$ rostopic list
/clock
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/gazebo_gui/parameter_descriptions
/gazebo_gui/parameter_updates
/gazebo_ros_control/pid_gains/gripper/parameter_descriptions
/gazebo_ros_control/pid_gains/gripper/parameter_updates
/gazebo_ros_control/pid_gains/gripper/state
/gazebo_ros_control/pid_gains/gripper_sub/parameter_descriptions
/gazebo_ros_control/pid_gains/gripper_sub/parameter_updates
/gazebo_ros_control/pid_gains/gripper_sub/state
/gazebo_ros_control/pid_gains/joint1/parameter_descriptions
/gazebo_ros_control/pid_gains/joint1/parameter_updates
/gazebo_ros_control/pid_gains/joint1/state
/gazebo_ros_control/pid_gains/joint2/parameter_descriptions
/gazebo_ros_control/pid_gains/joint2/parameter_updates
/gazebo_ros_control/pid_gains/joint2/state
/gazebo_ros_control/pid_gains/joint3/parameter_descriptions
/gazebo_ros_control/pid_gains/joint3/parameter_updates
/gazebo_ros_control/pid_gains/joint3/state
/gazebo_ros_control/pid_gains/joint4/parameter_descriptions
/gazebo_ros_control/pid_gains/joint4/parameter_updates
/gazebo_ros_control/pid_gains/joint4/state
/om_with_tb3/camera/parameter_descriptions
/om_with_tb3/camera/parameter_updates
/om_with_tb3/camera/rgb/camera_info
/om_with_tb3/camera/rgb/image_raw
/om_with_tb3/camera/rgb/image_raw/compressed
/om_with_tb3/camera/rgb/image_raw/compressed/parameter_descriptions
/om_with_tb3/camera/rgb/image_raw/compressed/parameter_updates
/om_with_tb3/camera/rgb/image_raw/compressedDepth
/om_with_tb3/camera/rgb/image_raw/compressedDepth/parameter_descriptions
/om_with_tb3/camera/rgb/image_raw/compressedDepth/parameter_updates
/om_with_tb3/camera/rgb/image_raw/theora
/om_with_tb3/camera/rgb/image_raw/theora/parameter_descriptions
/om_with_tb3/camera/rgb/image_raw/theora/parameter_updates
/om_with_tb3/cmd_vel
/om_with_tb3/gripper_position/command
/om_with_tb3/gripper_sub_position/command
/om_with_tb3/imu
/om_with_tb3/joint1_position/command
/om_with_tb3/joint2_position/command
/om_with_tb3/joint3_position/command
/om_with_tb3/joint4_position/command
/om_with_tb3/joint_states
/om_with_tb3/odom
/om_with_tb3/scan
/rosout
/rosout_agg
/tf
/tf_static
$ rostopic pub /om_with_tb3/joint4_position/command std_msgs/Float64 "data: -0.21" --once

Pick and Place

We provide the pick and place example for mobile manipulation. This example is used smach(task-level architecture) to send action to robot.

Bringup gazebo simulator

$ roslaunch open_manipulator_with_tb3_gazebo rooms.launch use_platform:=false

Launch navigation, moveIt!

$ roslaunch open_manipulator_with_tb3_tools rooms.launch use_platform:=false

Launch task controller

$ roslaunch open_manipulator_with_tb3_tools task_controller.launch 

TIP: Smach provides state graph. Try to run smach viewer and how to robot can pick and place. rosrun smach_viewer smach_viewer.py