Code and models for the Crane+V2 (4DOF arm + gripper) with the MoveIt! Motion Planning Framework for ROS.
- Environment Setup
- Package Description
- Quick Start
- Setting Up a VM
- Crane Plus Control: Parameter Tuning
This package has only been tested on Ubuntu 16.04 LTS with ROS Kinetic. ROS is currently only stable on Python 2.7 due to compatibility with legacy packages.
If you do not have Ubuntu 16.04 LTS or want to run on Windows machine, an option is to download the ISO and install on a VM such as VMWare Workstation Player (setup) or Virtualbox (setup). See below for further instructions.
If you wish to run ROS along with Python 3 in Anaconda, please create a py2.7 conda environment for ROS.
$ conda create -n ros_env python=2.7 anaconda -y
$ source activate ros_env
(ros_env) $ pip install -U catkin_pkg rospkg
crane_plus_control: Parameter tuning and benchmarking nodes
crane_plus_description: CAD files and URDF (Unified Robot Description Format) model of CRANE+V2
crane_plus_gripper: Node that controls the gripper of CRANE+V2
crane_plus_hardware: Launch file that configures the settings for use with CRANE+V2 hardware
crane_plus_ikfast_arm_plugin: Custom inverse kinematics plugin for CRANE+V2 in the MoveIt! framework
crane_plus_joint_state_publisher: Node that converts servo status messages (dynamixel_msgs/JointState
message type) output by the Dynamixel servo controller to ROS sensor_msgs/JointState
message type
crane_plus_moveit_config: Parameters and launch files for using CRANE+V2 with MoveIt! framework
crane_plus_simulation: Launch file that configures the settings for simulating CRANE+V2 in Gazebo
-
Download and run the
crane_plus_setup.sh
script to install ROS, clone and builds the repository as well as other required packages. This will take some time. Reboot after installation finishes.$ curl -O 'https://raw.githubusercontent.com/charyeezy/crane_plus_v2_motion_planning/master/crane_plus_setup.sh' $ chmod u+x crane_plus_setup.sh && ./crane_plus_setup.sh $ sudo reboot
If you want to download all dependencies at once, do install
crane_plus_setup_FULL.sh
. -
Launch the CRANE+V2 robot model either through the hardware interface or through simulation.
$ roslaunch crane_plus_control control.launch
sim: [default=true] Launch robot model in simulation or in hardware.
rviz: [default=true] Launch MoveIt! with Rviz.
gui: [default=true] Launch the Gazebo GUI.
tuning: [default=false] Launch in tuning mode or in normal mode.
-
Visualise motion planning through MoveIt RViz.
$ roslaunch crane_plus_moveit_config crane_plus.launch
[OPTIONAL] Control headlessly for named poses. You can optionally set
rviz:=false
.Select from list of named states: [vertical, backbend, resting, low_fwd_reach, pose1, pose2, pose3, pose4, pose5, pose6, pose7, pose8, pose9, pose10, pose11, pose12, pose13, pose14]
$ roslaunch crane_plus_moveit_config crane_plus.launch robot_execution:=true rviz:=false $ roslaunch crane_plus_control named_pose.launch pose:=resting
-
Download the Ubuntu 16.04 LTS ISO and install on a VM such as VMWare Workstation Player (setup) or Virtualbox (setup).
-
Install VMWare tools for VMWare Workstation Player or VirtualBox Guest Additions for Virtualbox.
$ sudo apt-get install open-vm-tools