Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Create KinematicReachability Database
Description: Create KinematicReachability Database with OpenRaveKeywords: kinematicsreachability
Tutorial Level:
Contents
Introduction
cd /path/to/workspace git clone https://github.com/jsk-ros-pkg/jsk_common.git jsk-ros-pkg/jsk_common git clone https://github.com/jsk-ros-pkg/openrave_planning.git jsk-ros-pkg/openrave_planning
config file
sample_robot_openrave.xml
<robot file="/path/to/sample_robot.dae"> <manipulator name="larm" > <base>CHEST_LINK3</base> <effector>LARM_LINK7</effector> <Translation>0 0 0</Translation> <rotationaxis>0 0 0 0</rotationaxis> </manipulator> </robot>
single thread
rosdep install openrave rosmake openrave export PATH=`rospack find openrave`/bin:$PATH export PYTHONPATH=`openrave-config --python-dir`:$PYTHONPATH export OPENRAVE_HOME=/path/to/workspace/sample_robot cd /path/to/worksace rosrun openrave openrave.py --database kinematicreachability --robot=sample_robot_openrave.xml --manipname=larm --xyzdelta=0.8 --quatdelta=0.8
show
rosrun openrave openrave.py --database kinematicreachability --robot=sample_robot_openrave.xml --manipname=larm --show
multi thread
Before running the following commands, do not forget to run roscore.
export PATH=`rospack find openrave`/bin:$PATH export PYTHONPATH=`openrave-config --python-dir`:$PYTHONPATH:$(rospack find openrave_database) export OPENRAVE_HOME=/path/to/workspace/sample_robot rosdep intall paralle_util rosmake parallel_util cd /path/to/workspace rosrun parallel_util workmanagerlauncher.py --module=kinematicreachability_ros --launchservice='60*localhost' --args="--robot=/path/to/sample_robot_openrave.xml --manipname=larm --xyzdelta=0.08 --quatdelta=0.8"
NOTICE: /path/to/sample_robot_openrave.xml should be abolute.