## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = Using Gazebo with hrpsys ## multi-line description to be displayed in search ## description = this tutorials show how to use gazebo with hrpsys-base ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link= [[rtmros_common/Tutorials/AddRobotsEnvironmentsHrpsysSimulator]] ## next.1.link= ## what level user is this tutorial for ## level= IntermediateCategory ## keywords = #################################### <<IncludeCSTemplate(TutorialCSHeaderTemplate)>> <<TableOfContents(4)>> == Install (12.04 Ubuntu) == {{{ sudo aptitude install ros-hydro-hrpsys-gazebo-general }}} Add following line to .bashrc {{{ source `rospack find hrpsys_gazebo_general`/setup.sh }}} == Try Demo Program of Biped Robot == === Launch gazebo === Open Terminal and run gazebo {{{ roslaunch hrpsys_gazebo_general gazebo_samplerobot_no_controllers.launch }}} === Move robot with ros topic === You can move robot by ros topic even if hrpsys is not launched. '''/SampleRobot/joint_command''' is topic to send joint command. '''/SampleRobot/robot_state''' is topic to get robot state. Following command is the sample to send joint command. Joint command is not interpolated and robot joint moves to the target angle very fast. {{{ rostopic pub /SampleRobot/joint_command hrpsys_gazebo_msgs/JointCommand "{position: [0.0, -0.34906585039886595, 0.0, 0.8203047484373336, -0.47123889803846897, 0.0, 0.5235987755982987, 0.0, 0.0, -1.0471975511965974, 0.15707963267948954, -0.11344640137963141, 0.6370451769779297, 0.0, -0.34906585039886595, 0.0, 0.8203047484373336, -0.47123889803846897, 0.0, 0.5235987755982987, 0.0, 0.0, -1.0471975511965974, -0.15707963267948954, -0.11344640137963141, -0.6370451769779297, 0.0, 0.0, 0.0], kpv_position: [250.0, 250.0, 250.0, 250.0, 250.0, 250.0, 160.0, 120.0, 100.0, 160.0, 100.0, 100.0, 100.0, 250.0, 250.0, 250.0, 250.0, 250.0, 250.0, 160.0, 120.0, 100.0, 160.0, 100.0, 100.0, 100.0, 250.0, 250.0, 250.0], desired_controller_period_ms: 1}" --once rostopic pub /SampleRobot/joint_command hrpsys_gazebo_msgs/JointCommand "{position: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0], kpv_position: [250.0, 250.0, 250.0, 250.0, 250.0, 250.0, 160.0, 120.0, 100.0, 160.0, 100.0, 100.0, 100.0, 250.0, 250.0, 250.0, 250.0, 250.0, 250.0, 160.0, 120.0, 100.0, 160.0, 100.0, 100.0, 100.0, 250.0, 250.0, 250.0], desired_controller_period_ms: 1}" --once }}} === Move robot with hrpsys === Launch another terminal and start hrpsys-base {{{ rtmlaunch hrpsys_gazebo_general samplerobot_hrpsys_bringup.launch }}} Then, launch another terminal and make a robot walk {{{ rosrun hrpsys_ros_bridge test-samplerobot.py }}} {{http://wiki.ros.org/rtmros_common/Tutorials/HrpsysGazebo?action=AttachFile&do=get&target=GazeboSampleRobot.png|sample robot in gazebo|width="640"}} == TIPS == === Gazebo version === ros-hydro-hrpsys-gazebo-general depends on ros-hydro-gazebo-ros (gazebo version 1.9.*). HrpsysGazebo is available with newer gazebo (gazebo versin 3 or 4) if you install from source. https://github.com/start-jsk/rtmros_gazebo === Kill gazebo process === When you get the following error, previous gazebo process remains. Plese do '''pkill gzserver''' and try again. {{{ roslaunch hrpsys_gazebo_general gazebo_samplerobot_no_controllers.launch ... Exception [Master.cc:50] Unable to start server[Address already in use]. There is probably another Gazebo process running. ... }}} === Teleport robot to initial position === Even if a robot falls down in gazebo, the robot can teleport to the initial position by '''Ctrl + Shift + R''' === Kinematics mode === Kinematics mode, which fixes the base link of the robot in the reference position of hrpsys, is available by adding option KINEMATICS_MODE. {{{{ rtmlaunch hrpsys_gazebo_general samplerobot_hrpsys_bringup.launch KINEMATICS_MODE:=true }}}} ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE