This is a ROS package for representing the kinematic reachability of robots: differentiable reachability map.
This is a scalar-valued function in task space that is positive only in the region reachable by the robot's end-effector. The main feature is that the scalar-valued function is continuous and differentiable with respect to task-space coordinates. This allows us to formulate the reachability conditions of the robot's end-effectors using reachability maps in continuous optimization for motion planning. The differentiable reachability map is learned using a support vector machine from a sample set of end-effector poses generated from a robot kinematic model.
It is assumed that ROS is installed.
-
Install mc_rtc
Installation via apt is recommended. See here. -
Install jrl-qp
$ git clone https://github.com/jrl-umi3218/jrl-qp -b topic/BlockStructure --recursive
$ mkdir build
$ cd build
$ cmake .. -DBUILD_TESTING=OFF -DBUILD_BENCHMARKS=OFF
$ make
$ make install
- Setup catkin workspace and build
$ mkdir -p ~/ros/ws_differentiable_rmap/src
$ cd ~/ros/ws_differentiable_rmap
$ wstool init src
$ wstool set -t src isri-aist/optmotiongen git@github.com:isri-aist/optmotiongen.git -v ver2 --git -y
$ wstool set -t src isri-aist/differentiable_rmap git@github.com:isri-aist/differentiable_rmap.git --git -y
$ wstool update -t src
$ source /opt/ros/${ROS_DISTRO}/setup.bash
$ rosdep install -y -r --from-paths src --ignore-src
$ catkin build -DCMAKE_BUILD_TYPE=RelWithDebInfo -DENABLE_JRLQP=ON
You can reproduce the results of this video.
Run either FK-based or IK-based sampling.
FK-based sampling:
$ roslaunch differentiable_rmap rmap_sampling_simple_2dof_manipulator.launch
IK-based sampling:
$ roslaunch differentiable_rmap rmap_sampling_simple_2dof_manipulator.launch use_ik:=true
$ roslaunch differentiable_rmap rmap_training.launch sampling_space:=R2
$ roslaunch differentiable_rmap rmap_visualization.launch sampling_space:=R2
$ roslaunch differentiable_rmap rmap_planning.launch sampling_space:=R2
$ rosrun differentiable_rmap JointSpaceUniformSampling.py
$ rosrun differentiable_rmap TaskSpaceDensityEstimation.py
The following image will be displayed.