Skip to content

Latest commit

 

History

History
65 lines (50 loc) · 4.52 KB

File metadata and controls

65 lines (50 loc) · 4.52 KB

fourr_kazerounian_moveit_config

Introduction and useful notes

This repository contains the configuration and launch files of the 4R planar manipulator first proposed by Kazerounian & Wang in their paper. The package has been generated by the MoveIt! setup assistant (see MoveIt! Setup Assistant tutorial), using the URDF from the fourr_kazerounian_description package.

The repository contains the main move_group node to be used for planning through a move_group interface. The purpose of this package in the project is to provide a use case for the moveit_dp_redundancy_resolution algorithms and to validate the ROS implementation of the MATLAB prototypes by comparing their results.

The following modifications are necessary to the original package generated by the setup assistant to make it work with redundancy resolution:

  • The move_group.launch file needs to be modified to include the move_group/MoveGroupDPRedundancyResolutionService capability.
  • Several parameters must be loaded on the parameter server in order for the moveit_dp_redundancy_resolution library to execute. Refer to the moveit_dp_redundancy_resolution documentation for more info.
  • An objective function description must be given. See file config/objective_function.xml and moveit_dp_redundancy_resoltion documentation for additional info.
  • When creating this package with the MoveIt! Setup Assistant, a non-redundant planning group has to be defined. This is the group of joints used by the state_space_grid module to compute inverse kinematics with the redundant joints fixed. Since the chosen redundant joint might not be redundant in practice for certain workspace paths, more than one non-redundant planning group may need to be defined and used if necessary. As instance, the non-redundant planning group q2_q3_q4 is defined in the 4R planar arm model, but a different planning group, such as q1_q3_q4 could be defined, being q2 the redundant joint.
  • The moveit_dp_redundancy_resolution module publishes the planned joint-space trajectory to the ros topic /move_group/plot_planned_path. The same messages are also automatically collected in a bag file which is written to the bagfiles/ directory of the output path (see moveit_dp_redundancy_resolution package documentation for more information about the output_path parameter). Alternatively, the same bag file can be obtained by recording the /move_group/plot_planned_path topic by using the rosbag client application. The time series corresponding to the joint positions, velocities and accelerations are published to the aforementioned topic and thus recorded in the bag file. The tool selected for their visualization is rqt_multiplot, which is able to deal with both live data and off-line bag files. With respect to rqt_plot, it can pick the timestamps from the ROS messages published to the topic, thus generating reliable plots. It can also visualize more time series together on the same plot and display more plots together on the same view. The configuration of rqt_multiplot allowing all this for the 4R planar manipulator by Kazerounian & Wang is included in the config/ folder of this package. When launching rqt_multiplot for the first time, open this configuration file!

Getting Started

Prerequisites

The following prerequisites are necessary to get started (other configuration may work but were not validated):

  • Ubuntu 16.04
  • ROS Kinetic
  • Moveit

Compilation and development node setup

  • Create new catkin workspace folder (or use an existing one):
mkdir -p catkin_ws/src
  • Place yourself in the src folder
cd catkin_ws/src
  • Clone this repository
git clone https://github.com/unisa-acg/moveit_dp_redundancy_resolution.git
  • To build the workspace run
catkin_make
  • If developing with a specific IDE, in order to generate the configuration files for it, it might be convenient to use catkin build instead, e.g. (for Eclipse)
catkin build  --force-cmake -G"Eclipse CDT4 - Unix Makefiles"
  • Source the setup file to configure the environment variables
source devel/setup.sh
  • Add the full-path instruction above at the end of the .bashrc file so as not to configure the environment variables manually in each shell, e.g.
source /home/<username>/catkin_ws/devel/setup.sh
  • Launch the nodes to verify that no runtime error occurs
roslaunch fourr_kazerounian_moveit_config demo.launch
roslaunch fourr_kazerounian_controller fourr_kazerounian_controller.launch