├── README.md ├── actor ├── files │ ├── box_square_full.gif │ ├── full_animation.gif │ ├── skel_full.gif │ ├── skel_traj_full.gif │ └── traj_full.gif └── tutorial.md ├── add_laser ├── files │ └── Add_laser_pioneer.png ├── tutorial.md └── tutorial_6+.md ├── aerodynamics ├── files │ ├── airfoil_coordinates.png │ ├── angleOfAttack.jpg │ ├── cessna_demo.png │ ├── cp_location.png │ ├── lift_curve.png │ └── lift_curve_simplified.png └── tutorial.md ├── animated_box ├── tutorial.md ├── tutorial_4.md └── tutorial_6.md ├── apply_force_torque ├── files │ ├── apply_force.png │ ├── apply_force_offset.png │ ├── apply_torque.png │ └── insert_models.png └── tutorial.md ├── architecture └── tutorial.md ├── attach_gripper ├── files │ ├── Mobile_base.png │ ├── Mobile_base_large.png │ ├── Simple_mobile_manipulator.png │ ├── manipulator-1.9+.sdf │ ├── manipulator.sdf │ ├── model-1.9+.config │ ├── model-1.9+.sdf │ ├── model.config │ └── model.sdf ├── tutorial-1.9+.md └── tutorial.md ├── attach_meshes ├── files │ ├── Mobile_robot_chassis_1.png │ ├── Mobile_robot_chassis_2.png │ └── Mobile_robot_chassis_3.png └── tutorial.md ├── build_model ├── files │ └── box.sdf ├── tutorial-7.md └── tutorial.md ├── build_robot ├── files │ ├── My_robot_box.png │ ├── My_robot_caster.png │ ├── My_robot_caster_left_wheel.png │ ├── My_robot_caster_wheels.png │ └── Simple-robot-driving.png └── tutorial.md ├── build_world ├── files │ ├── added_models_to_empty_world.png │ ├── empty_rts.png │ ├── empty_translate_rotate_highlighted.png │ ├── empty_world.png │ ├── empty_world_insert_highlighted.png │ ├── empty_world_simple_shapes_highlighted.png │ └── simple_shapes.png ├── tutorial.md ├── tutorial_1.9.md └── tutorial_2.2.md ├── building_editor ├── files │ ├── add_level.png │ ├── add_stairs.png │ ├── add_walls.png │ ├── add_windows_doors.png │ ├── color_texture_inspector.png │ ├── color_texture_palette.png │ ├── custom_color.png │ ├── edit_level.png │ ├── edit_name.png │ ├── edit_stairs.png │ ├── edit_walls.png │ ├── edit_windows_doors.png │ ├── editor_zones.png │ ├── empty_editor.png │ ├── final_model_angles.png │ ├── floorplan.png │ ├── import_step_1.png │ ├── import_step_2.png │ ├── save_dialog.png │ ├── saved_building.png │ └── view_floorplan.png └── tutorial.md ├── camera_distortion ├── files │ ├── distorted_camera_image_visualizer.png │ ├── distorted_camera_inserted.png │ └── distorted_camera_topic_visualizer.png └── tutorial.md ├── camera_save ├── files │ ├── camera_tutorial.world │ ├── my_camera.gif │ └── my_camera.mp4 └── tutorial.md ├── clone_simulation ├── files │ ├── gazebo_clone_sim.png │ └── sidebyside.png └── tutorial.md ├── collide_bitmask ├── files │ └── collide_bitmask.png └── tutorial.md ├── color_model ├── files │ ├── collada_default_color.png │ ├── collada_head.png │ ├── component_affects.png │ ├── dark_colored_wheels.png │ ├── green_led.png │ ├── head.dae │ ├── head_texture.png │ ├── light_and_material_interaction.png │ ├── lit_world.world │ ├── model.config │ ├── model.no_materials.sdf │ ├── model.sdf │ ├── model_files.png │ ├── model_in_gazebo.png │ ├── repeated.material │ ├── robot_before_after.png │ ├── scaled_ogre_script.png │ ├── seamless_texture.png │ └── texture_ambient_diffuse.png └── tutorial_7.md ├── components └── tutorial.md ├── contact_sensor ├── tutorial.md ├── tutorial_4-0.md └── tutorial_7-0.md ├── contain_plugin ├── CMakeLists.txt ├── example_world.png ├── lamppostlight.gif ├── movingvolume.gif ├── tutorial_7.md └── tutorial_9.md ├── contrib_code └── tutorial.md ├── custom_messages ├── files │ └── map.png ├── tutorial-8.0.md └── tutorial.md ├── dem ├── files │ ├── gazebo_dem_merged.png │ ├── gazebo_sthelens.png │ ├── glcf_search_tool.png │ ├── mtsthelens_after.zip │ ├── mtsthelens_before.zip │ ├── qgis.png │ ├── qgis_las_palmas.png │ └── volcano.world ├── tutorial.md └── tutorial_3.0.md ├── drcsim_animate_joints ├── files │ ├── joint_animation.py │ └── joint_animation_v4v5.py └── tutorial.md ├── drcsim_atlas_mixer ├── files │ ├── Nanokonotrol.jpg │ ├── Qual_2_start.png │ └── drill.yaml └── tutorial.md ├── drcsim_atlas_robot_interface ├── files │ └── atlas_interface │ │ ├── CMakeLists.txt │ │ ├── Makefile │ │ ├── README │ │ ├── examples │ │ ├── example.cpp │ │ └── example.launch │ │ ├── package.xml │ │ └── src │ │ └── atlas_interface.cpp └── tutorial.md ├── drcsim_atlas_siminterface ├── files │ ├── Asi_walk.png │ └── walk.py └── tutorial.md ├── drcsim_bdi_examples ├── files │ ├── Gazebo_with_drc_robot.png │ └── atlas_5steps.png └── tutorial.md ├── drcsim_control_sync ├── files │ ├── Atlas_sync.png │ ├── Sync_exhaust_stats.png │ ├── Sync_stats.png │ ├── atlas_sync.launch │ └── my_atlas_controller.cpp └── tutorial.md ├── drcsim_create_atlas_world ├── files │ ├── atlas.launch │ ├── atlas_spawned.png │ ├── insert_models.png │ └── shapes_toolbar.png └── tutorial.md ├── drcsim_fakewalking ├── files │ ├── Gazebo_with_drc_robot.png │ └── Gazebo_with_drc_robot_drcsim4.png └── tutorial.md ├── drcsim_grasp_sandia ├── files │ ├── sandia_hand_closed.png │ └── sandia_hand_open.png └── tutorial.md ├── drcsim_install └── tutorial.md ├── drcsim_keyboard_teleop ├── files │ └── Atlas_keyboard_teleop.png └── tutorial.md ├── drcsim_launchfiles ├── files │ ├── drcpractice4_atlas_v4_robotiq.png │ ├── irobot.png │ ├── robotiq.png │ ├── sandia.png │ └── versions.png └── tutorial.md ├── drcsim_modify_world ├── files │ ├── Gazebo_with_drc_robot.png │ └── Gazebo_with_drc_robot_and_primitives.png └── tutorial.md ├── drcsim_multisense ├── files │ ├── Atlas_launch.png │ ├── Atlas_rviz.png │ └── Atlas_rviz_spindle.png └── tutorial.md ├── drcsim_robotiq_hand ├── files │ ├── robotiq_hand_closed.png │ ├── robotiq_hand_open.png │ └── robotiq_hand_rviz.png └── tutorial.md ├── drcsim_ros_cmds ├── files │ ├── CMakeLists.txt │ ├── publish_joint_commands.cpp │ └── publish_joint_commands_v4v5.cpp └── tutorial.md ├── drcsim_ros_python ├── files │ ├── Traj_data2.yaml │ └── traj_yaml.py └── tutorial.md ├── drcsim_set_joint_damping └── tutorial.md ├── drcsim_switch_modes ├── files │ └── demo.py └── tutorial.md ├── drcsim_vehicle └── tutorial.md ├── drcsim_vehicle_atlas └── tutorial.md ├── drcsim_visualization ├── files │ ├── Blank_rviz_2.7.png │ ├── Rviz_accumulated_scans_2.7.png │ ├── Rviz_atlas_in_pelvis_frame_new_2.7.png │ ├── Rviz_atlas_with_camera_2.7.png │ └── robot_model_2.7.png └── tutorial.md ├── elevators └── tutorial.md ├── extrude_svg ├── files │ ├── add-custom-shape.png │ ├── custom-wheel.png │ ├── extrude-link.png │ ├── import-link.png │ ├── inkscape-blank.png │ ├── inkscape-grids-tab.png │ ├── inkscape-page-tab.png │ ├── inkscape-select-all.png │ ├── inkscape-simple-wheel.png │ ├── inkscape_logo.jpg │ ├── save-model.png │ └── wheel.svg └── tutorial.md ├── flashlight_plugin ├── files │ ├── example.gif │ ├── extendedplugin.png │ ├── extendedsetting.png │ ├── flashlight.png │ ├── init.png │ └── switchcolors.gif └── tutorial_9-3.md ├── fluids └── tutorial.md ├── force_torque_sensor ├── files │ ├── force_torque_demo.png │ ├── force_torque_joint_locations.svg │ ├── force_torque_on_fixed.png │ ├── force_torque_on_revolute.png │ ├── force_torque_toppled.png │ ├── force_torque_toppled_diagram.png │ ├── force_torque_toppled_diagram.svg │ └── force_torque_tutorial.world └── tutorial.md ├── friction └── tutorial.md ├── ftu ├── tutorial1.md ├── tutorial2.md └── tutorial3.md ├── gazebojs_camera_topics ├── files │ ├── frame_0007.jpeg │ └── world.png └── tutorial.md ├── gazebojs_install ├── files │ └── gazebojs_overview.png └── tutorial.md ├── gazebojs_install_mac ├── files │ └── gazebojs_overview.png └── tutorial.md ├── gazebojs_models └── tutorial.md ├── gazebojs_pubsub └── tutorial.md ├── gravity_compensation ├── files │ ├── gravity_compensation.png │ ├── joint_control_gui.png │ ├── mass_on_rails.png │ ├── model_error.png │ ├── p_control.png │ ├── pid_control.png │ ├── plot_example.png │ └── robonaut.gif └── tutorial.md ├── gui_overlay ├── files │ ├── spawn_button.png │ ├── spawn_sphere.png │ └── time.png ├── tutorial.md ├── tutorial7.md └── tutorial9.md ├── guided_a ├── files │ ├── tut2_1.png │ ├── tut3_1.png │ └── tut3_2.png ├── tutorial1.md ├── tutorial2.md ├── tutorial3.md ├── tutorial4.md └── tutorial5.md ├── guided_b ├── files │ ├── ftu3-boot-screen.png │ ├── ftu3-bottom-toolbar.png │ ├── ftu3-gazebo-menu.png │ ├── ftu3-menu-options.png │ ├── ftu3-mouse-controls.png │ ├── ftu3-panels.png │ ├── ftu3-scene.png │ ├── ftu3-top-toolbar.png │ ├── ftu4-caster_align.png │ ├── ftu4-caster_joint.png │ ├── ftu4-caster_joint_ball.png │ ├── ftu4-caster_joint_z.png │ ├── ftu4-caster_resize.png │ ├── ftu4-caster_sphere.png │ ├── ftu4-chassis_height.png │ ├── ftu4-chassis_scale.png │ ├── ftu4-copy_tool.png │ ├── ftu4-depth_camera.png │ ├── ftu4-depth_camera_joint.png │ ├── ftu4-depth_camera_joint_fixed.png │ ├── ftu4-depth_camera_translate.png │ ├── ftu4-editor_box.png │ ├── ftu4-exit.png │ ├── ftu4-follow.png │ ├── ftu4-follower_plugin.png │ ├── ftu4-insert_tab.png │ ├── ftu4-joint_dialog.png │ ├── ftu4-model_database.png │ ├── ftu4-model_plugin_inspector.png │ ├── ftu4-model_plugin_inspector_done.png │ ├── ftu4-model_tree.png │ ├── ftu4-save_as.png │ ├── ftu4-scale_tool.png │ ├── ftu4-snap_tool.png │ ├── ftu4-wheel_align_x.png │ ├── ftu4-wheel_align_y.png │ ├── ftu4-wheel_align_y_reverse.png │ ├── ftu4-wheel_castor_z.png │ ├── ftu4-wheel_joint.png │ ├── ftu4-wheel_joint_child.png │ ├── ftu4-wheel_joints.png │ ├── ftu4-wheel_paste.png │ ├── ftu4-wheel_pose_z.png │ ├── ftu4-wheel_rotate.png │ ├── ftu4-wheel_rotation_axis.png │ ├── ftu4-wheel_visual.png │ ├── ftu4_castor_sphere.png │ ├── gazebo8_model_editor_ui.png │ └── gazebo8_model_editor_ui.svg ├── tutorial1.md ├── tutorial2.md ├── tutorial3.md ├── tutorial5.md ├── tutorial6.md ├── tutorial7.md ├── tutorial8.md └── tutorial9.md ├── guided_i ├── files │ ├── blender_import.png │ ├── blender_shrunk.png │ ├── blender_translate.png │ ├── box_no_noise.jpg │ ├── freecad_base.png │ ├── topic_selector.png │ ├── velodyne_base.dae │ ├── velodyne_collisions.jpg │ ├── velodyne_complete_visual.jpg │ ├── velodyne_drawing.png │ ├── velodyne_hdl32.tar.gz │ ├── velodyne_inertia.jpg │ ├── velodyne_inertia_good.jpg │ ├── velodyne_insertion.png │ ├── velodyne_joint_cmd_widget.png │ ├── velodyne_joints.jpg │ ├── velodyne_no_noise.png │ ├── velodyne_noisy.png │ ├── velodyne_rays.jpg │ ├── velodyne_top.dae │ ├── velodyne_top_visual_rotated.jpg │ ├── velodyne_top_visual_unrotated.jpg │ └── velodyne_vis_no_noise.png ├── tutorial1.md ├── tutorial2.md ├── tutorial3.md ├── tutorial4.md ├── tutorial5.md └── tutorial6.md ├── gz_topic └── tutorial.md ├── gzweb_development ├── tutorial.md └── tutorial_1.9.md ├── gzweb_install ├── tutorial.md ├── tutorial_1.9.md └── tutorial_7.md ├── haptix_comm ├── files │ ├── CMakeLists.txt │ └── visual-studio.png └── tutorial.md ├── haptix_install ├── files │ ├── gazebo_version.png │ ├── haptix_overview.png │ ├── haptix_version.png │ ├── haptix_version2.png │ ├── ifconfig.png │ └── ipconfig.png └── tutorial.md ├── haptix_logging ├── files │ ├── logging_1.png │ └── logging_2.png └── tutorial.md ├── haptix_luke_hand └── tutorial.md ├── haptix_matlab ├── files │ └── matlab.png └── tutorial.md ├── haptix_optitrack ├── files │ ├── arm_alignment.png │ ├── armcloseup.png │ ├── camera_preview.PNG │ ├── data_streaming.PNG │ ├── diy_target.png │ ├── fullsetup.png │ ├── groundplane.PNG │ ├── haptix_osrf.ttp │ ├── head_alignment.png │ ├── monitor.png │ ├── motive_icon.PNG │ ├── motive_start.PNG │ ├── new_rigid_body.PNG │ ├── perspective_view.PNG │ ├── premade_trackers.png │ ├── selection.PNG │ └── spheres.png └── tutorial.md ├── haptix_scoring_plugin └── tutorial.md ├── haptix_sim_api └── tutorial.md ├── haptix_tactors ├── files │ ├── CMakeLists.txt │ ├── arduino_sketch.c │ ├── glove_back.jpg │ ├── glove_front.jpg │ ├── grasp_sim.png │ ├── tactors.cc │ ├── tactors_soldered.jpg │ └── teensy_pinout.png └── tutorial.md ├── haptix_teleop ├── files │ ├── gui_teleop.png │ └── keyboard.png └── tutorial.md ├── haptix_unboxing ├── files │ ├── desktop.png │ └── haptix_setup_diagram_final.svg └── tutorial.md ├── haptix_world_sim_api ├── files │ ├── custom_haptix.world │ ├── custom_world.c │ └── custom_world.m └── tutorial.md ├── hydra └── tutorial.md ├── hydra_gzjs_pub └── tutorial.md ├── hydrodynamics ├── files │ ├── leftmenu.png │ └── submarines.png └── tutorial.md ├── import_mesh ├── files │ ├── TutorialMeshDuck.png │ └── my_mesh.world └── tutorial.md ├── inertia ├── files │ ├── gazebo_inertia.jpg │ └── meshlab.jpg └── tutorial.md ├── install_dependencies_from_source ├── files │ └── gazebo_dependency_tree.svg ├── tutorial-8.md └── tutorial.md ├── install_from_source ├── tutorial_8.md ├── tutorial_default.md └── tutorial_old.md ├── install_on_mac ├── tutorial_11-0.md └── tutorial_9-0.md ├── install_on_windows └── tutorial_11-0.md ├── install_other_linux ├── tutorial-9.0.md └── tutorial.md ├── install_ubuntu ├── tutorial_11.0.md └── tutorial_9-0.md ├── install_unstable └── tutorial.md ├── instrument_hdf5_datasets ├── files │ └── hdf5.png └── tutorial.md ├── introspection ├── files │ ├── CMakeLists.txt │ ├── empty.world │ ├── introspectable_plugin.cc │ ├── introspection_registration.png │ ├── introspection_registration.xml │ ├── introspection_subscription.png │ ├── introspection_subscription.xml │ ├── readme │ └── watcher.cc └── tutorial.md ├── joint_events ├── apply_force.png ├── apply_force_torque.png ├── joint_event.world ├── joint_test_world.png ├── select_needle_link.png ├── sim_event_topic_response.png ├── topic_visualizer.png ├── torque_needle.png └── tutorial.md ├── kinematic_loop ├── four_bar.png ├── four_bar_sdf │ ├── README.md │ ├── model.config │ ├── model.sdf │ └── model.sdf.erb ├── four_bar_split.png ├── four_bar_split_fixed_sdf │ ├── README.md │ ├── model.config │ ├── model.sdf │ └── model.sdf.erb ├── four_bar_split_fixed_urdf │ ├── README.md │ ├── model.config │ ├── model.urdf │ └── model.urdf.erb └── tutorial.md ├── led_plugin ├── files │ ├── LED.png │ └── example.gif └── tutorial_9-3.md ├── lightmap ├── table_lightmap.png ├── table_no_lighting.png ├── table_no_lightmap.png └── tutorial.md ├── lockstep_physics_sensors ├── files │ ├── lockstep_highres_camera.png │ ├── lockstep_regular_camera.png │ ├── no_lockstep.png │ └── topic_selector.png └── tutorial.md ├── log_filtering ├── tutorial.md └── tutorial_4-0.md ├── logging_playback ├── files │ ├── data_logger.png │ ├── playback_gui.png │ └── recordings.png └── tutorial.md ├── logical_camera_sensor ├── files │ ├── tutorial_logical_camera.world │ ├── tutorial_logical_camera.world.png │ ├── tutorial_logical_camera_aabb_false_positive.world │ ├── tutorial_logical_camera_aabb_false_positive.world.png │ └── wireframe.material └── tutorial_7+.md ├── manifest.xml ├── manifest_to_tsv.rb ├── model_contrib └── tutorial.md ├── model_editor ├── files │ ├── empty_editor.png │ ├── empty_editor_7.png │ ├── model_editor_car.png │ ├── model_editor_car_done.png │ ├── model_editor_edit_name.png │ ├── model_editor_existing_model.png │ ├── model_editor_insert_mesh.png │ ├── model_editor_insert_mesh_7.png │ ├── model_editor_insert_mesh_8.png │ ├── model_editor_inspector.png │ ├── model_editor_inspector_7.png │ ├── model_editor_joint.png │ ├── model_editor_joint_7.png │ ├── model_editor_joint_inspector.png │ ├── model_editor_joint_inspector_7.png │ ├── model_editor_save_dialog.png │ ├── model_editor_save_dialog_7.png │ ├── model_editor_simple_shapes.png │ ├── model_editor_simple_shapes_7.png │ └── undo_redo.png ├── tutorial.md ├── tutorial_6.md └── tutorial_7.md ├── model_population ├── files │ ├── can_population.world │ ├── gazebo_population.png │ ├── model_list.png │ └── model_list_6-0.png └── tutorial.md ├── model_structure ├── files │ └── box.sdf └── tutorial.md ├── modifying_world ├── files │ ├── tutorialPhysicsTab.png │ ├── tutorialSceneTab.png │ └── tutorialSceneTabExpanded.png └── tutorial.md ├── nested_model ├── files │ ├── nested_model.png │ └── nested_model_joint.png └── tutorial.md ├── occupiedevent └── tutorial.md ├── oculus ├── files │ ├── display_setup.png │ └── display_setup2.png ├── tutorial.md └── tutorial_3.md ├── parallel ├── files │ ├── dual_pr2.jpg │ ├── pendulums.jpg │ ├── pr2.jpg │ ├── revolute_joint_test_spit_unthrottled.png │ ├── revolute_joint_test_unthrottled.png │ ├── run_dual_pr2_test.bash │ ├── run_pendulums_test.bash │ ├── run_pr2_test.bash │ └── show_parallel_results.py └── tutorial.md ├── performance_metrics └── tutorial.md ├── physics_params ├── files │ └── cone_pyramid.png └── tutorial.md ├── player_camera └── tutorial.md ├── player_laser └── tutorial.md ├── player_position └── tutorial.md ├── plugins_hello_world ├── tutorial-2.2.md └── tutorial-6.md ├── plugins_model ├── tutorial.md └── tutorial_1-9.md ├── plugins_random_velocity └── tutorial-6.md ├── plugins_world ├── tutorial-7-8.md ├── tutorial.md └── tutorial1_9.md ├── plugins_world_properties ├── tutorial.md ├── tutorial_1-9.md ├── tutorial_2-2.md └── tutorial_7.md ├── preset_manager ├── files │ ├── inertia_ratio_pendulum.svg │ ├── preset_example.world │ ├── preset_example_sdf1_6.world │ ├── preset_plot_annotated.png │ ├── switch_profiles.sh │ ├── switch_profiles_sdf1_6.sh │ └── worldtab.png ├── tutorial.md ├── tutorial_3.md └── tutorial_7.md ├── process └── tutorial.md ├── profiler ├── files │ ├── Remotery_OdePhysics.png │ ├── SensorManagerLoop.png │ └── gzserverLoop.png └── tutorial.md ├── quick_start └── tutorial.md ├── random_numbers └── tutorial.md ├── ros2_installing ├── figs │ ├── gazebo_ros_diff_drive.png │ └── gazebo_ros_diff_drive_lin_vel.gif └── tutorial.md ├── ros2_overview └── tutorial.md ├── ros_advanced ├── RosGUI.png ├── pioneer_flying.png └── tutorial.md ├── ros_comm ├── Coke_Can.png ├── Coke_Can_Flying.png ├── FloatingCokeCan.png ├── HoverCoke.png ├── rotating_link.png └── tutorial.md ├── ros_control ├── Gazebo_ros_transmission.png ├── rqt_controller_tuning.png ├── rqt_dynamnic_reconfigure_pid.png └── tutorial.md ├── ros_depth_camera ├── depth_camera_rviz.png ├── depth_camera_scene.png ├── files │ └── kinect.zip ├── rviz_topics.png └── tutorial.md ├── ros_gzplugins ├── figs │ ├── camera.png │ ├── cameraView.png │ ├── gazebo_laser_scan.png │ └── rviz_laser_scan.png └── tutorial.md ├── ros_installing ├── figs │ └── 800px-EmptyGazebo.png └── tutorial.md ├── ros_overview ├── figs │ └── 775px-Gazebo_ros_api.png └── tutorial.md ├── ros_plugins └── tutorial.md ├── ros_roslaunch ├── figs │ ├── GasStation.png │ ├── Gas_baxter.png │ └── PR2_GasStation.png └── tutorial.md ├── ros_urdf ├── figs │ ├── Rrbot_rviz.png │ └── Swinging_Arm.png └── tutorial.md ├── ros_wrapper_versions └── tutorial.md ├── screenshot ├── files │ ├── screenshot_icon_gzclient.png │ └── screenshot_icon_gzclient_6-0.png ├── tutorial.md └── tutorial_1-9.md ├── sensor_noise ├── files │ ├── Noisy_camera_visualizer.png │ ├── Noisy_laser_inserted.png │ ├── Noisy_laser_visualizer.png │ └── Topic_visualizer.png ├── tutorial-7_0.md └── tutorial.md ├── set_velocity ├── examples │ ├── set_vel_plugin │ │ ├── CMakeLists.txt │ │ ├── include │ │ │ ├── ode_perfect_angular.hh │ │ │ ├── ode_perfect_linear.hh │ │ │ ├── ode_perfect_velocity.hh │ │ │ └── pid_link.hh │ │ └── src │ │ │ ├── SetJointVelocityPlugin.cpp │ │ │ └── SetLinkVelocityPlugin.cpp │ └── set_velocity.world ├── pictures │ ├── set_joint_velocity.gif │ └── set_link_velocity.gif └── tutorial_7.md ├── simple_gripper ├── files │ ├── Simple-gripper-1.png │ ├── Simple-gripper-joints.png │ ├── Simple-gripper-joints_5.png │ ├── Simple_gripper_joint_control_1_4.png │ ├── Simple_gripper_joint_control_1_5.png │ ├── gripper.world │ ├── model.config │ └── simple_gripper.sdf ├── tutorial.md └── tutorial_1-9.md ├── static_map_plugin ├── files │ ├── static_map_models.png │ └── static_map_plugin.jpg └── tutorial.md ├── stereo_glasses └── tutorial.md ├── system_plugin ├── tutorial.md ├── tutorial_3-0.md ├── tutorial_5-0.md ├── tutorial_7-0.md └── tutorial_8-0.md ├── topics_subscribe ├── tutorial.md ├── tutorial_1-9.md └── tutorial_2-2.md ├── torsional_friction ├── files │ ├── box_and_sphere.png │ └── radius_depth.png └── tutorial.md ├── tutorial_contrib └── tutorial.md ├── visual_layers ├── files │ ├── layers_1.png │ └── layers_2.png └── tutorial.md └── wide_angle_camera ├── files ├── 180.png ├── 360.png ├── c_1.gif ├── c_2.gif ├── dfov.gif ├── dfov2.gif ├── f.gif ├── fun.gif ├── fun_inv.gif └── r.gif └── tutorial.md /README.md: -------------------------------------------------------------------------------- 1 | # Gazebo Tutorials # 2 | 3 | This repository contains the source for each gazebo tutorial found on [Gazebo Tutorials](http://classic.gazebosim.org/tutorials). 4 | 5 | ## Tips for creating tutorials 6 | 7 | 1. Add images and/or videos where appropriate so that the reader has a reference image to compare their simulation instance against. 8 | -------------------------------------------------------------------------------- /actor/files/box_square_full.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/actor/files/box_square_full.gif -------------------------------------------------------------------------------- /actor/files/full_animation.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/actor/files/full_animation.gif -------------------------------------------------------------------------------- /actor/files/skel_full.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/actor/files/skel_full.gif -------------------------------------------------------------------------------- /actor/files/skel_traj_full.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/actor/files/skel_traj_full.gif -------------------------------------------------------------------------------- /actor/files/traj_full.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/actor/files/traj_full.gif -------------------------------------------------------------------------------- /add_laser/files/Add_laser_pioneer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/add_laser/files/Add_laser_pioneer.png -------------------------------------------------------------------------------- /aerodynamics/files/airfoil_coordinates.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/aerodynamics/files/airfoil_coordinates.png -------------------------------------------------------------------------------- /aerodynamics/files/angleOfAttack.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/aerodynamics/files/angleOfAttack.jpg -------------------------------------------------------------------------------- /aerodynamics/files/cessna_demo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/aerodynamics/files/cessna_demo.png -------------------------------------------------------------------------------- /aerodynamics/files/cp_location.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/aerodynamics/files/cp_location.png -------------------------------------------------------------------------------- /aerodynamics/files/lift_curve.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/aerodynamics/files/lift_curve.png -------------------------------------------------------------------------------- /aerodynamics/files/lift_curve_simplified.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/aerodynamics/files/lift_curve_simplified.png -------------------------------------------------------------------------------- /apply_force_torque/files/apply_force.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/apply_force_torque/files/apply_force.png -------------------------------------------------------------------------------- /apply_force_torque/files/apply_force_offset.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/apply_force_torque/files/apply_force_offset.png -------------------------------------------------------------------------------- /apply_force_torque/files/apply_torque.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/apply_force_torque/files/apply_torque.png -------------------------------------------------------------------------------- /apply_force_torque/files/insert_models.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/apply_force_torque/files/insert_models.png -------------------------------------------------------------------------------- /attach_gripper/files/Mobile_base.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/attach_gripper/files/Mobile_base.png -------------------------------------------------------------------------------- /attach_gripper/files/Mobile_base_large.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/attach_gripper/files/Mobile_base_large.png -------------------------------------------------------------------------------- /attach_gripper/files/Simple_mobile_manipulator.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/attach_gripper/files/Simple_mobile_manipulator.png -------------------------------------------------------------------------------- /attach_gripper/files/manipulator-1.9+.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://my_gripper 7 | 1.3 0 0.1 0 0 0 8 | 9 | 10 | 11 | model://my_robot 12 | 0 0 0 0 0 0 13 | 14 | 15 | 16 | mobile_base::chassis 17 | simple_gripper::riser 18 | 19 | 20 | 0 21 | 0 22 | 23 | 0 0 1 24 | 25 | 26 | 27 | 28 | 29 | model://hokuyo 30 | 1.3 0 0.3 0 0 0 31 | 32 | 33 | 34 | hokuyo::link 35 | simple_gripper::palm 36 | 37 | 0 0 1 38 | 39 | 0 40 | 0 41 | 42 | 43 | 44 | 45 | 46 | 47 | -------------------------------------------------------------------------------- /attach_gripper/files/manipulator.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://my_gripper 7 | 1.3 0 0.1 0 0 0 8 | 9 | 10 | 11 | model://my_robot 12 | 0 0 0 0 0 0 13 | 14 | 15 | 16 | mobile_base::chassis 17 | simple_gripper::riser 18 | 19 | 20 | 21 | 22 | model://hokuyo 23 | 1.3 0 0.3 0 0 0 24 | 25 | 26 | 27 | hokuyo::link 28 | simple_gripper::palm 29 | 30 | 31 | 32 | 33 | -------------------------------------------------------------------------------- /attach_gripper/files/model-1.9+.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | Simple Mobile Manipulator 4 | 1.0 5 | manipulator.sdf 6 | 7 | 8 | My Name 9 | me@my.email 10 | 11 | 12 | 13 | My simple mobile manipulator 14 | 15 | 16 | -------------------------------------------------------------------------------- /attach_gripper/files/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | Simple Mobile Manipulator 4 | 1.0 5 | manipulator.sdf 6 | 7 | 8 | My Name 9 | me@my.email 10 | 11 | 12 | 13 | My simple mobile manipulator 14 | 15 | 16 | -------------------------------------------------------------------------------- /attach_gripper/tutorial-1.9+.md: -------------------------------------------------------------------------------- 1 | # Overview 2 | 3 | **Prerequisites:** 4 | 5 | [Make a Mobile Robot](/tutorials/?tut=build_robot) 6 | 7 | [Make a Simple Gripper](/tutorials/?tut=simple_gripper) 8 | 9 | This tutorial explains how to create a composite robot from existing robot parts, i.e. mobile base, simple arm and simple gripper. 10 | 11 | # Robot Components 12 | 13 | Start up gazebo and make sure you can load the models from the two previous tutorials. 14 | 15 | ## Mobile Base 16 | 17 | 1. Per instructions in [Make a Mobile Robot](/tutorials/?tut=build_robot) tutorial, you should have a mobile base robot at your disposal: 18 | 19 | [[file:files/Mobile_base.png|640px]] 20 | 21 | 1. For this exercise, modify `~/.gazebo/models/my_robot/model.sdf` to make the model larger so it can accommodate the gripper we are about to append to it: 22 | 23 | gedit ~/.gazebo/models/my_robot/model.sdf 24 | 25 | update the contents to make the model body larger and re-position the wheels accordingly: 26 | 27 | 28 | 29 | [[file:files/Mobile_base_large.png|640px]] 30 | 31 | ## Assembling a Composite Robot 32 | 33 | 1. To create a mobile robot with a simple gripper attached, create a new models directory 34 | 35 | mkdir ~/.gazebo/models/simple_mobile_manipulator 36 | 37 | And edit the model config file: 38 | 39 | gedit ~/.gazebo/models/simple_mobile_manipulator/model.config 40 | 41 | populate it with the following contents: 42 | 43 | 44 | 45 | 1. Next, create the model SDF file: 46 | 47 | gedit ~/.gazebo/models/simple_mobile_manipulator/manipulator.sdf 48 | 49 | and populate with following contents: 50 | 51 | 52 | 53 | 1. Make sure the `model.config` and `manipulator.sdf` files above are saved, start Gazebo and spawn the model above by using the **insert** tab and choosing **Simple Mobile Manipulator** model. You should see something similar to: 54 | 55 | [[file:files/Simple_mobile_manipulator.png|640px]] 56 | -------------------------------------------------------------------------------- /attach_gripper/tutorial.md: -------------------------------------------------------------------------------- 1 | # Overview 2 | 3 | **Prerequisites:** 4 | 5 | [Make a Mobile Robot](/tutorials/?tut=build_robot) 6 | 7 | [Make a Simple Gripper](/tutorials/?tut=simple_gripper) 8 | 9 | This tutorial explains how to create a composite robot from existing robot parts, i.e. mobile base, simple arm and simple gripper. 10 | 11 | # Robot Components 12 | 13 | Start up gazebo and make sure you can load the models from the two previous tutorials. 14 | 15 | ## Mobile Base 16 | 17 | 1. Per instructions in [Make a Mobile Robot](/tutorials/?tut=build_robot) tutorial, you should have a mobile base robot at your disposal: 18 | 19 | [[file:files/Mobile_base.png|640px]] 20 | 21 | 1. For this exercise, modify `~/.gazebo/models/my_robot/model.sdf` to make the model larger so it can accommodate the gripper we are about to append to it: 22 | 23 | gedit ~/.gazebo/models/my_robot/model.sdf 24 | 25 | update the contents to make the model body larger and re-position the wheels accordingly: 26 | 27 | 28 | 29 | [[file:files/Mobile_base_large.png|640px]] 30 | 31 | ## Assembling a Composite Robot 32 | 33 | 1. To create a mobile robot with a simple gripper attached, create a new models directory 34 | 35 | mkdir ~/.gazebo/models/simple_mobile_manipulator 36 | 37 | And edit the model config file: 38 | 39 | gedit ~/.gazebo/models/simple_mobile_manipulator/model.config 40 | 41 | populate it with the following contents: 42 | 43 | 44 | 45 | 1. Next, create the model SDF file: 46 | 47 | gedit ~/.gazebo/models/simple_mobile_manipulator/manipulator.sdf 48 | 49 | and populate with following contents: 50 | 51 | 52 | 53 | 1. Make sure the `model.config` and `manipulator.sdf` files above are saved, start Gazebo and spawn the model above by using the **insert** tab and choosing **Simple Mobile Manipulator** model. You should see something similar to: 54 | 55 | [[file:files/Simple_mobile_manipulator.png|640px]] 56 | -------------------------------------------------------------------------------- /attach_meshes/files/Mobile_robot_chassis_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/attach_meshes/files/Mobile_robot_chassis_1.png -------------------------------------------------------------------------------- /attach_meshes/files/Mobile_robot_chassis_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/attach_meshes/files/Mobile_robot_chassis_2.png -------------------------------------------------------------------------------- /attach_meshes/files/Mobile_robot_chassis_3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/attach_meshes/files/Mobile_robot_chassis_3.png -------------------------------------------------------------------------------- /build_model/files/box.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 0 0 0.5 0 0 0 5 | true 6 | 7 | 8 | 1.0 9 | 10 | 11 | 0.083 12 | 0.0 13 | 0.0 14 | 0.083 15 | 0.0 16 | 0.083 17 | 18 | 19 | 20 | 21 | 22 | 1 1 1 23 | 24 | 25 | 26 | 27 | 28 | 29 | 1 1 1 30 | 31 | 32 | 33 | 34 | 35 | 36 | -------------------------------------------------------------------------------- /build_robot/files/My_robot_box.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_robot/files/My_robot_box.png -------------------------------------------------------------------------------- /build_robot/files/My_robot_caster.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_robot/files/My_robot_caster.png -------------------------------------------------------------------------------- /build_robot/files/My_robot_caster_left_wheel.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_robot/files/My_robot_caster_left_wheel.png -------------------------------------------------------------------------------- /build_robot/files/My_robot_caster_wheels.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_robot/files/My_robot_caster_wheels.png -------------------------------------------------------------------------------- /build_robot/files/Simple-robot-driving.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_robot/files/Simple-robot-driving.png -------------------------------------------------------------------------------- /build_world/files/added_models_to_empty_world.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_world/files/added_models_to_empty_world.png -------------------------------------------------------------------------------- /build_world/files/empty_rts.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_world/files/empty_rts.png -------------------------------------------------------------------------------- /build_world/files/empty_translate_rotate_highlighted.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_world/files/empty_translate_rotate_highlighted.png -------------------------------------------------------------------------------- /build_world/files/empty_world.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_world/files/empty_world.png -------------------------------------------------------------------------------- /build_world/files/empty_world_insert_highlighted.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_world/files/empty_world_insert_highlighted.png -------------------------------------------------------------------------------- /build_world/files/empty_world_simple_shapes_highlighted.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_world/files/empty_world_simple_shapes_highlighted.png -------------------------------------------------------------------------------- /build_world/files/simple_shapes.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/build_world/files/simple_shapes.png -------------------------------------------------------------------------------- /building_editor/files/add_level.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/add_level.png -------------------------------------------------------------------------------- /building_editor/files/add_stairs.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/add_stairs.png -------------------------------------------------------------------------------- /building_editor/files/add_walls.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/add_walls.png -------------------------------------------------------------------------------- /building_editor/files/add_windows_doors.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/add_windows_doors.png -------------------------------------------------------------------------------- /building_editor/files/color_texture_inspector.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/color_texture_inspector.png -------------------------------------------------------------------------------- /building_editor/files/color_texture_palette.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/color_texture_palette.png -------------------------------------------------------------------------------- /building_editor/files/custom_color.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/custom_color.png -------------------------------------------------------------------------------- /building_editor/files/edit_level.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/edit_level.png -------------------------------------------------------------------------------- /building_editor/files/edit_name.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/edit_name.png -------------------------------------------------------------------------------- /building_editor/files/edit_stairs.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/edit_stairs.png -------------------------------------------------------------------------------- /building_editor/files/edit_walls.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/edit_walls.png -------------------------------------------------------------------------------- /building_editor/files/edit_windows_doors.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/edit_windows_doors.png -------------------------------------------------------------------------------- /building_editor/files/editor_zones.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/editor_zones.png -------------------------------------------------------------------------------- /building_editor/files/empty_editor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/empty_editor.png -------------------------------------------------------------------------------- /building_editor/files/final_model_angles.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/final_model_angles.png -------------------------------------------------------------------------------- /building_editor/files/floorplan.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/floorplan.png -------------------------------------------------------------------------------- /building_editor/files/import_step_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/import_step_1.png -------------------------------------------------------------------------------- /building_editor/files/import_step_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/import_step_2.png -------------------------------------------------------------------------------- /building_editor/files/save_dialog.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/save_dialog.png -------------------------------------------------------------------------------- /building_editor/files/saved_building.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/saved_building.png -------------------------------------------------------------------------------- /building_editor/files/view_floorplan.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/building_editor/files/view_floorplan.png -------------------------------------------------------------------------------- /camera_distortion/files/distorted_camera_image_visualizer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/camera_distortion/files/distorted_camera_image_visualizer.png -------------------------------------------------------------------------------- /camera_distortion/files/distorted_camera_inserted.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/camera_distortion/files/distorted_camera_inserted.png -------------------------------------------------------------------------------- /camera_distortion/files/distorted_camera_topic_visualizer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/camera_distortion/files/distorted_camera_topic_visualizer.png -------------------------------------------------------------------------------- /camera_save/files/camera_tutorial.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 0 0 2.5 0 -0 0 6 | 7 | 8 | 9 | 10 | 1 1 1 11 | 12 | 13 | 14 | 15 | 16 | 17 | 0 0 1 0 0 0 18 | 19 | 20 | true 21 | -1 0 2 0 1 0 22 | 23 | 24 | 25 | 26 | 0.1 0.1 0.1 27 | 28 | 29 | 30 | 31 | 32 | 33 | /tmp/camera_save_tutorial 34 | 35 | 1.047 36 | 37 | 1920 38 | 1080 39 | 40 | 41 | 0.1 42 | 100 43 | 44 | 45 | 1 46 | 30 47 | 48 | 49 | 50 | 51 | 52 | -------------------------------------------------------------------------------- /camera_save/files/my_camera.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/camera_save/files/my_camera.gif -------------------------------------------------------------------------------- /camera_save/files/my_camera.mp4: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/camera_save/files/my_camera.mp4 -------------------------------------------------------------------------------- /clone_simulation/files/gazebo_clone_sim.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/clone_simulation/files/gazebo_clone_sim.png -------------------------------------------------------------------------------- /clone_simulation/files/sidebyside.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/clone_simulation/files/sidebyside.png -------------------------------------------------------------------------------- /collide_bitmask/files/collide_bitmask.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/collide_bitmask/files/collide_bitmask.png -------------------------------------------------------------------------------- /color_model/files/collada_default_color.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/collada_default_color.png -------------------------------------------------------------------------------- /color_model/files/collada_head.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/collada_head.png -------------------------------------------------------------------------------- /color_model/files/component_affects.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/component_affects.png -------------------------------------------------------------------------------- /color_model/files/dark_colored_wheels.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/dark_colored_wheels.png -------------------------------------------------------------------------------- /color_model/files/green_led.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/green_led.png -------------------------------------------------------------------------------- /color_model/files/head_texture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/head_texture.png -------------------------------------------------------------------------------- /color_model/files/light_and_material_interaction.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/light_and_material_interaction.png -------------------------------------------------------------------------------- /color_model/files/lit_world.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 0.4 0.4 0.4 1 6 | 0.25 0.25 0.25 1 7 | false 8 | 9 | 10 | 0.7 0.7 0.7 0 11 | 1 1 1 0 12 | -1 -1 -1 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /color_model/files/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Example Model For Color Tutorial 5 | 1.0 6 | model.sdf 7 | 8 | 9 | YOUR NAME HERE 10 | YOUR EMAIL HERE 11 | 12 | 13 | 14 | Example of adding color to a model 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /color_model/files/model.no_materials.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | 1 1 1 10 | 11 | 12 | 13 | 14 | -0.2 0 -0.25 0 1.57079 0 15 | 16 | 17 | 0.05 18 | 0.02 19 | 20 | 21 | 22 | 23 | 0.2 0 -0.25 0 1.57079 0 24 | 25 | 26 | 0.05 27 | 0.02 28 | 29 | 30 | 31 | 32 | 0.225 0.225 0.25 0 0 0 33 | 34 | 35 | 0.003 36 | 37 | 38 | 39 | 40 | 41 | 42 | 0.5 0.5 0.5 43 | 44 | 45 | 46 | 47 | 0 0 0.25 0 0 -2.5 48 | 49 | 50 | 0.25 51 | 52 | 53 | 54 | 55 | 56 | 57 | -------------------------------------------------------------------------------- /color_model/files/model_files.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/model_files.png -------------------------------------------------------------------------------- /color_model/files/model_in_gazebo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/model_in_gazebo.png -------------------------------------------------------------------------------- /color_model/files/repeated.material: -------------------------------------------------------------------------------- 1 | material RepeatedTexture 2 | { 3 | technique 4 | { 5 | pass 6 | { 7 | texture_unit 8 | { 9 | // Relative to the location of the material script 10 | texture ../textures/seamless_texture.png 11 | // Repeat the texture over the surface (4 per face) 12 | scale 0.5 0.5 13 | } 14 | } 15 | } 16 | } 17 | -------------------------------------------------------------------------------- /color_model/files/robot_before_after.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/robot_before_after.png -------------------------------------------------------------------------------- /color_model/files/scaled_ogre_script.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/scaled_ogre_script.png -------------------------------------------------------------------------------- /color_model/files/seamless_texture.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/seamless_texture.png -------------------------------------------------------------------------------- /color_model/files/texture_ambient_diffuse.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/color_model/files/texture_ambient_diffuse.png -------------------------------------------------------------------------------- /contain_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.12) 2 | project(tutorial_contain_plugin) 3 | 4 | find_package(gazebo REQUIRED) 5 | 6 | add_library(TurnOnLightPlugin SHARED TurnOnLightPlugin.cpp) 7 | target_include_directories(TurnOnLightPlugin PRIVATE ${GAZEBO_INCLUDE_DIRS}) 8 | target_link_libraries(TurnOnLightPlugin PUBLIC ${GAZEBO_LIBRARIES}) 9 | target_compile_options(TurnOnLightPlugin PUBLIC ${GAZEBO_CXX_FLAGS}) 10 | -------------------------------------------------------------------------------- /contain_plugin/example_world.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/contain_plugin/example_world.png -------------------------------------------------------------------------------- /contain_plugin/lamppostlight.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/contain_plugin/lamppostlight.gif -------------------------------------------------------------------------------- /contain_plugin/movingvolume.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/contain_plugin/movingvolume.gif -------------------------------------------------------------------------------- /custom_messages/files/map.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/custom_messages/files/map.png -------------------------------------------------------------------------------- /dem/files/gazebo_dem_merged.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/dem/files/gazebo_dem_merged.png -------------------------------------------------------------------------------- /dem/files/gazebo_sthelens.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/dem/files/gazebo_sthelens.png -------------------------------------------------------------------------------- /dem/files/glcf_search_tool.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/dem/files/glcf_search_tool.png -------------------------------------------------------------------------------- /dem/files/mtsthelens_after.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/dem/files/mtsthelens_after.zip -------------------------------------------------------------------------------- /dem/files/mtsthelens_before.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/dem/files/mtsthelens_before.zip -------------------------------------------------------------------------------- /dem/files/qgis.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/dem/files/qgis.png -------------------------------------------------------------------------------- /dem/files/qgis_las_palmas.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/dem/files/qgis_las_palmas.png -------------------------------------------------------------------------------- /dem/files/volcano.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://sun 7 | 8 | 9 | 10 | true 11 | 12 | 13 | 14 | 15 | file://media/dem/mtsthelens_129.dem 16 | 150 150 50 17 | 0 0 -685 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | file://media/materials/textures/dirt_diffusespecular.png 27 | file://media/materials/textures/flat_normal.png 28 | 1 29 | 30 | 31 | file://media/materials/textures/grass_diffusespecular.png 32 | file://media/materials/textures/flat_normal.png 33 | 1 34 | 35 | 36 | file://media/materials/textures/fungus_diffusespecular.png 37 | file://media/materials/textures/flat_normal.png 38 | 1 39 | 40 | 41 | 2 42 | 5 43 | 44 | 45 | 4 46 | 5 47 | 48 | file://media/dem/mtsthelens_129.dem 49 | 150 150 50 50 | 0 0 -685 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | -------------------------------------------------------------------------------- /drcsim_atlas_mixer/files/Nanokonotrol.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_atlas_mixer/files/Nanokonotrol.jpg -------------------------------------------------------------------------------- /drcsim_atlas_mixer/files/Qual_2_start.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_atlas_mixer/files/Qual_2_start.png -------------------------------------------------------------------------------- /drcsim_atlas_mixer/files/drill.yaml: -------------------------------------------------------------------------------- 1 | # back left leg right leg left arm right arm LH RH 2 | 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 cyl 0 cyl 0" 3 | 1: "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -0.4271259903907776 1.262315034866333 1.4657480716705322 -0.9703150391578674 -0.2356692999601364 -0.6822677254676819 cyl 0 cyl 0" 4 | 2: "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -1 1 0 -1 0 0 cyl 0 cyl 0" 5 | 3: "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 2.0 0 cyl 0 cyl 0" 6 | 4: "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 -2.0 0 cyl 0 cyl 0" 7 | 5: "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 2.0 cyl 0 cyl 0" 8 | 6: "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 -2.0 cyl 0 cyl 0" 9 | 7: "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 cyl 0 cyl 1" 10 | 8: "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 cyl 0 sph 1" 11 | -------------------------------------------------------------------------------- /drcsim_atlas_robot_interface/files/atlas_interface/Makefile: -------------------------------------------------------------------------------- 1 | include $(shell rospack find mk)/cmake.mk -------------------------------------------------------------------------------- /drcsim_atlas_robot_interface/files/atlas_interface/README: -------------------------------------------------------------------------------- 1 | This package contains a library that can be used as a stand-in for the 2 | AtlasRobotInterface library. It implements the same API as that library but on 3 | the back end, instead of talking to a physical Atlas, it talks to 4 | Gazebo/DRCSim via ROS. 5 | 6 | To try it out: 7 | 8 | == Configure and build == 9 | 10 | * Download AtlasRobotInterface v2.0.2 and unpack it somewhere. Let's call 11 | that directory /work/AtlasRobotInterface_2.0.2. 12 | 13 | * Build and install drcsim as usual (or you could install the latest 2.7.x 14 | package via apt-get). 15 | 16 | * Source the drcsim setup file, e.g.: 17 | 18 | source /usr/share/drcsim/setup.sh 19 | 20 | * Add this package's directory (atlas_interface) to your 21 | ROS_PACKAGE_PATH, e.g.: 22 | 23 | export ROS_PACKAGE_PATH=`pwd`:$ROS_PACKAGE_PATH 24 | 25 | * Set the ATLAS_ROBOT_INTERFACE_ROOT environment variable to point to where 26 | you unpacked AtlasRobotInterface, e.g.: 27 | 28 | export ATLAS_ROBOT_INTERFACE_ROOT=/work/AtlasRobotInterface_2.0.2 29 | 30 | * Build this package: 31 | 32 | roscd atlas_interface 33 | make 34 | 35 | == Running == 36 | 37 | * Try the example launch file: 38 | 39 | roslaunch atlas_interface example.launch 40 | 41 | That will bring up Atlas in an empty world, with the example program 42 | (example/example.cpp) running. The intent is that the example is the kind of 43 | user code that is normally linked against the AtlasRobotInterface library and 44 | used with a physical robot. That same code can instead be linked against 45 | atlas_interface and be used with a simulated robot. 46 | 47 | == Development / testing == 48 | 49 | * The details of integrating this library into your system will depend on your 50 | code and build system. In general, the idea is to compile against the headers 51 | provided by AtlasRobotInterface, but link against libatlas_interface.so, 52 | provided here. 53 | -------------------------------------------------------------------------------- /drcsim_atlas_robot_interface/files/atlas_interface/examples/example.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | -------------------------------------------------------------------------------- /drcsim_atlas_siminterface/files/Asi_walk.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_atlas_siminterface/files/Asi_walk.png -------------------------------------------------------------------------------- /drcsim_bdi_examples/files/Gazebo_with_drc_robot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_bdi_examples/files/Gazebo_with_drc_robot.png -------------------------------------------------------------------------------- /drcsim_bdi_examples/files/atlas_5steps.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_bdi_examples/files/atlas_5steps.png -------------------------------------------------------------------------------- /drcsim_control_sync/files/Atlas_sync.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_control_sync/files/Atlas_sync.png -------------------------------------------------------------------------------- /drcsim_control_sync/files/Sync_exhaust_stats.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_control_sync/files/Sync_exhaust_stats.png -------------------------------------------------------------------------------- /drcsim_control_sync/files/Sync_stats.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_control_sync/files/Sync_stats.png -------------------------------------------------------------------------------- /drcsim_control_sync/files/atlas_sync.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /drcsim_create_atlas_world/files/atlas.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /drcsim_create_atlas_world/files/atlas_spawned.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_create_atlas_world/files/atlas_spawned.png -------------------------------------------------------------------------------- /drcsim_create_atlas_world/files/insert_models.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_create_atlas_world/files/insert_models.png -------------------------------------------------------------------------------- /drcsim_create_atlas_world/files/shapes_toolbar.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_create_atlas_world/files/shapes_toolbar.png -------------------------------------------------------------------------------- /drcsim_fakewalking/files/Gazebo_with_drc_robot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_fakewalking/files/Gazebo_with_drc_robot.png -------------------------------------------------------------------------------- /drcsim_fakewalking/files/Gazebo_with_drc_robot_drcsim4.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_fakewalking/files/Gazebo_with_drc_robot_drcsim4.png -------------------------------------------------------------------------------- /drcsim_grasp_sandia/files/sandia_hand_closed.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_grasp_sandia/files/sandia_hand_closed.png -------------------------------------------------------------------------------- /drcsim_grasp_sandia/files/sandia_hand_open.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_grasp_sandia/files/sandia_hand_open.png -------------------------------------------------------------------------------- /drcsim_keyboard_teleop/files/Atlas_keyboard_teleop.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_keyboard_teleop/files/Atlas_keyboard_teleop.png -------------------------------------------------------------------------------- /drcsim_launchfiles/files/drcpractice4_atlas_v4_robotiq.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_launchfiles/files/drcpractice4_atlas_v4_robotiq.png -------------------------------------------------------------------------------- /drcsim_launchfiles/files/irobot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_launchfiles/files/irobot.png -------------------------------------------------------------------------------- /drcsim_launchfiles/files/robotiq.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_launchfiles/files/robotiq.png -------------------------------------------------------------------------------- /drcsim_launchfiles/files/sandia.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_launchfiles/files/sandia.png -------------------------------------------------------------------------------- /drcsim_launchfiles/files/versions.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_launchfiles/files/versions.png -------------------------------------------------------------------------------- /drcsim_modify_world/files/Gazebo_with_drc_robot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_modify_world/files/Gazebo_with_drc_robot.png -------------------------------------------------------------------------------- /drcsim_modify_world/files/Gazebo_with_drc_robot_and_primitives.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_modify_world/files/Gazebo_with_drc_robot_and_primitives.png -------------------------------------------------------------------------------- /drcsim_multisense/files/Atlas_launch.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_multisense/files/Atlas_launch.png -------------------------------------------------------------------------------- /drcsim_multisense/files/Atlas_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_multisense/files/Atlas_rviz.png -------------------------------------------------------------------------------- /drcsim_multisense/files/Atlas_rviz_spindle.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_multisense/files/Atlas_rviz_spindle.png -------------------------------------------------------------------------------- /drcsim_robotiq_hand/files/robotiq_hand_closed.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_robotiq_hand/files/robotiq_hand_closed.png -------------------------------------------------------------------------------- /drcsim_robotiq_hand/files/robotiq_hand_open.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_robotiq_hand/files/robotiq_hand_open.png -------------------------------------------------------------------------------- /drcsim_robotiq_hand/files/robotiq_hand_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_robotiq_hand/files/robotiq_hand_rviz.png -------------------------------------------------------------------------------- /drcsim_ros_cmds/files/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.4.6) 2 | include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) 3 | 4 | # Set the build type. Options are: 5 | # Coverage : w/ debug symbols, w/o optimization, w/ code-coverage 6 | # Debug : w/ debug symbols, w/o optimization 7 | # Release : w/o debug symbols, w/ optimization 8 | # RelWithDebInfo : w/ debug symbols, w/ optimization 9 | # MinSizeRel : w/o debug symbols, w/ optimization, stripped binaries 10 | #set(ROS_BUILD_TYPE RelWithDebInfo) 11 | 12 | rosbuild_init() 13 | 14 | #set the default path for built executables to the "bin" directory 15 | set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) 16 | #set the default path for built libraries to the "lib" directory 17 | set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) 18 | 19 | #find gazebo include (FindPkgConfig) 20 | include (FindPkgConfig) 21 | if (PKG_CONFIG_FOUND) 22 | pkg_check_modules(GAZEBO gazebo) 23 | else() 24 | message(FATAL_ERROR "pkg-config is required; please install it") 25 | endif() 26 | 27 | # depends on DRCVehiclePlugin 28 | include_directories( 29 | ${GAZEBO_INCLUDE_DIRS} 30 | ) 31 | link_directories( 32 | ${GAZEBO_LIBRARY_DIRS} 33 | ) 34 | 35 | rosbuild_add_executable(publish_joint_commands src/publish_joint_commands.cpp) 36 | -------------------------------------------------------------------------------- /drcsim_ros_python/files/Traj_data2.yaml: -------------------------------------------------------------------------------- 1 | # you probably want to get a really wide window to edit this file. sorry 80 char windows. 2 | # the first column is the number of seconds to take to reach this point, relative to the previous point 3 | # spaces separate the following sub-vectors: 4 | # [ neck/body left_leg right_leg left_arm right_arm ] 5 | step_and_fall: 6 | - [1.0, "0 0 0 0.2 0 -0.1 0 0 0 0 0 -0.7 -1.2 1.4 -1.4 0 0 0 0 0 0 0 0 0 0 0 0 0 " ] 7 | - [0.5, "0 0 0 0 0 0.4 1.2 0.8 -1.4 0.2 0 -0.7 -1.2 1.4 -1.4 0 0 0 0 0 0 0 0 0 0 0 0 0 " ] 8 | - [1.5, "0 0 1 1 0 0 0 0 0.1 0 0 0 -0.2 0.4 -0.4 0 0 0 0 0 0 0 0 0 0 0 0 0 " ] 9 | - [1.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 " ] 10 | touchdown: 11 | - [2.0, "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -0.5 0 2 0 0 0 0.5 0 -2 0 0 " ] 12 | - [3.0, "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1.2 0 0.5 0 0 0 -1.2 0 -0.5 0 0 " ] 13 | - [1.0, "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -1.0 0 0 0 0 0 1.0 0 0 0 0 " ] 14 | touchdown_exhausted: 15 | - [2.0, "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -0.5 0 2 0 0 0 0.5 0 -2 0 0 " ] 16 | - [3.0, "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1.2 0 0.5 0 0 0 -1.2 0 -0.5 0 0 " ] 17 | - [1.0, "0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -1.0 -1.0 0 0 0 0 -1.0 1.0 0 0 0 0 " ] 18 | - [1.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 " ] 19 | -------------------------------------------------------------------------------- /drcsim_visualization/files/Blank_rviz_2.7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_visualization/files/Blank_rviz_2.7.png -------------------------------------------------------------------------------- /drcsim_visualization/files/Rviz_accumulated_scans_2.7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_visualization/files/Rviz_accumulated_scans_2.7.png -------------------------------------------------------------------------------- /drcsim_visualization/files/Rviz_atlas_in_pelvis_frame_new_2.7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_visualization/files/Rviz_atlas_in_pelvis_frame_new_2.7.png -------------------------------------------------------------------------------- /drcsim_visualization/files/Rviz_atlas_with_camera_2.7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_visualization/files/Rviz_atlas_with_camera_2.7.png -------------------------------------------------------------------------------- /drcsim_visualization/files/robot_model_2.7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/drcsim_visualization/files/robot_model_2.7.png -------------------------------------------------------------------------------- /extrude_svg/files/add-custom-shape.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/add-custom-shape.png -------------------------------------------------------------------------------- /extrude_svg/files/custom-wheel.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/custom-wheel.png -------------------------------------------------------------------------------- /extrude_svg/files/extrude-link.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/extrude-link.png -------------------------------------------------------------------------------- /extrude_svg/files/import-link.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/import-link.png -------------------------------------------------------------------------------- /extrude_svg/files/inkscape-blank.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/inkscape-blank.png -------------------------------------------------------------------------------- /extrude_svg/files/inkscape-grids-tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/inkscape-grids-tab.png -------------------------------------------------------------------------------- /extrude_svg/files/inkscape-page-tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/inkscape-page-tab.png -------------------------------------------------------------------------------- /extrude_svg/files/inkscape-select-all.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/inkscape-select-all.png -------------------------------------------------------------------------------- /extrude_svg/files/inkscape-simple-wheel.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/inkscape-simple-wheel.png -------------------------------------------------------------------------------- /extrude_svg/files/inkscape_logo.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/inkscape_logo.jpg -------------------------------------------------------------------------------- /extrude_svg/files/save-model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/extrude_svg/files/save-model.png -------------------------------------------------------------------------------- /flashlight_plugin/files/example.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/flashlight_plugin/files/example.gif -------------------------------------------------------------------------------- /flashlight_plugin/files/extendedplugin.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/flashlight_plugin/files/extendedplugin.png -------------------------------------------------------------------------------- /flashlight_plugin/files/extendedsetting.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/flashlight_plugin/files/extendedsetting.png -------------------------------------------------------------------------------- /flashlight_plugin/files/flashlight.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/flashlight_plugin/files/flashlight.png -------------------------------------------------------------------------------- /flashlight_plugin/files/init.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/flashlight_plugin/files/init.png -------------------------------------------------------------------------------- /flashlight_plugin/files/switchcolors.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/flashlight_plugin/files/switchcolors.gif -------------------------------------------------------------------------------- /force_torque_sensor/files/force_torque_demo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/force_torque_sensor/files/force_torque_demo.png -------------------------------------------------------------------------------- /force_torque_sensor/files/force_torque_on_fixed.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/force_torque_sensor/files/force_torque_on_fixed.png -------------------------------------------------------------------------------- /force_torque_sensor/files/force_torque_on_revolute.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/force_torque_sensor/files/force_torque_on_revolute.png -------------------------------------------------------------------------------- /force_torque_sensor/files/force_torque_toppled.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/force_torque_sensor/files/force_torque_toppled.png -------------------------------------------------------------------------------- /force_torque_sensor/files/force_torque_toppled_diagram.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/force_torque_sensor/files/force_torque_toppled_diagram.png -------------------------------------------------------------------------------- /ftu/tutorial1.md: -------------------------------------------------------------------------------- 1 | # Introduction 2 | 3 | Welcome to the Beginner Module! This section will guide you through the most basic features of Gazebo, with each tutorial building upon the last. We recommend following the tutorials in order. 4 | 5 | **Audience**: . 6 | 7 | **Module Goal**: You'll learn about Gazebo's Graphical User Interface (GUI) while building a simple, wheeled robot that follows a person. 8 | 9 | 10 | **Insert [Get Started button]** 11 | 12 | **Insert image of the robot they'll build** 13 | 14 | -------------------------------------------------------------------------------- /ftu/tutorial2.md: -------------------------------------------------------------------------------- 1 | # Intro 2 | 3 | Welcome to the Beginner Module! This module will guide you through the most 4 | basic features of Gazebo, with each tutorial building upon the last. We 5 | recommend following the tutorials in order. 6 | 7 | These tutorials are intended for those new to Gazebo and/or folks with **no programming or Linux experience**. 8 | 9 | # What is Gazebo? # 10 | 11 | Gazebo is a 3D dynamic simulator with the ability to accurately and 12 | efficiently simulate populations of robots in complex indoor and outdoor 13 | environments. While similar to game engines, Gazebo offers physics 14 | simulation at a much higher degree of fidelity, a suite of sensors, and 15 | interfaces for both users and programs. 16 | 17 | Typical uses of Gazebo include: 18 | 19 | * testing robotics algorithms, 20 | 21 | * designing robots, 22 | 23 | * performing regression testing with realistic scenarios 24 | 25 | A few key features of Gazebo include: 26 | 27 | * multiple physics engines, 28 | 29 | * a rich library of robot models and environments, 30 | 31 | * a wide variety of sensors, 32 | 33 | * convenient programmatic and graphical interfaces 34 | 35 | # System requirements # 36 | 37 | Gazebo is currently best used on [Ubuntu](http://www.ubuntu.com/download), a flavor of [Linux](https://en.wikipedia.org/wiki/Linux). You will need a computer that has: 38 | 39 | * A dedicated [GPU](https://en.wikipedia.org/wiki/Graphics_processing_unit), 40 | * Nvidia cards tend to work well in Ubuntu 41 | * A CPU that is at least an Intel I5, or equivalent, 42 | * At least 500MB of free disk space, 43 | * Ubuntu Trusty or later installed. 44 | 45 | # Installation Instructions for Ubuntu # 46 | 47 | 1. Download the [installer](http://osrf-distributions.s3.amazonaws.com/gazebo/gazebo6_install.sh). 48 | 49 | 1. Copy the following text: 50 | 51 | ``` 52 | chmod +x ~/Downloads/gazebo6_install.sh 53 | ``` 54 | 55 | 1. Press Alt-F2 56 | * A window with a prompt should appear in the upper left 57 | 58 | 1. Press Ctrl-V, and press Enter 59 | * The window will disappear 60 | 61 | 1. Copy in the following: 62 | 63 | ``` 64 | gnome-terminal --working-directory="~" -e "./Downloads/gazebo6_install.sh" 65 | ``` 66 | 67 | 1. Press Alt-F2 68 | * A window with a prompt should appear in the upper left 69 | 70 | 1. Press Ctrl-V, and press Enter 71 | * A new window will appear with a password prompt. 72 | 73 | 1. Enter your password, and press enter 74 | 75 | 1. Wait until the window disappears. 76 | 77 | # Run Gazebo # 78 | 79 | 1. Press Alt-F2 80 | 2. Type "gazebo", and press Enter. 81 | -------------------------------------------------------------------------------- /gazebojs_camera_topics/files/frame_0007.jpeg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gazebojs_camera_topics/files/frame_0007.jpeg -------------------------------------------------------------------------------- /gazebojs_camera_topics/files/world.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gazebojs_camera_topics/files/world.png -------------------------------------------------------------------------------- /gazebojs_install/files/gazebojs_overview.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gazebojs_install/files/gazebojs_overview.png -------------------------------------------------------------------------------- /gazebojs_install_mac/files/gazebojs_overview.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gazebojs_install_mac/files/gazebojs_overview.png -------------------------------------------------------------------------------- /gravity_compensation/files/gravity_compensation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gravity_compensation/files/gravity_compensation.png -------------------------------------------------------------------------------- /gravity_compensation/files/joint_control_gui.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gravity_compensation/files/joint_control_gui.png -------------------------------------------------------------------------------- /gravity_compensation/files/mass_on_rails.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gravity_compensation/files/mass_on_rails.png -------------------------------------------------------------------------------- /gravity_compensation/files/model_error.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gravity_compensation/files/model_error.png -------------------------------------------------------------------------------- /gravity_compensation/files/p_control.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gravity_compensation/files/p_control.png -------------------------------------------------------------------------------- /gravity_compensation/files/pid_control.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gravity_compensation/files/pid_control.png -------------------------------------------------------------------------------- /gravity_compensation/files/plot_example.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gravity_compensation/files/plot_example.png -------------------------------------------------------------------------------- /gravity_compensation/files/robonaut.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gravity_compensation/files/robonaut.gif -------------------------------------------------------------------------------- /gui_overlay/files/spawn_button.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gui_overlay/files/spawn_button.png -------------------------------------------------------------------------------- /gui_overlay/files/spawn_sphere.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gui_overlay/files/spawn_sphere.png -------------------------------------------------------------------------------- /gui_overlay/files/time.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/gui_overlay/files/time.png -------------------------------------------------------------------------------- /guided_a/files/tut2_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_a/files/tut2_1.png -------------------------------------------------------------------------------- /guided_a/files/tut3_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_a/files/tut3_1.png -------------------------------------------------------------------------------- /guided_a/files/tut3_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_a/files/tut3_2.png -------------------------------------------------------------------------------- /guided_b/files/ftu3-boot-screen.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu3-boot-screen.png -------------------------------------------------------------------------------- /guided_b/files/ftu3-bottom-toolbar.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu3-bottom-toolbar.png -------------------------------------------------------------------------------- /guided_b/files/ftu3-gazebo-menu.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu3-gazebo-menu.png -------------------------------------------------------------------------------- /guided_b/files/ftu3-menu-options.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu3-menu-options.png -------------------------------------------------------------------------------- /guided_b/files/ftu3-mouse-controls.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu3-mouse-controls.png -------------------------------------------------------------------------------- /guided_b/files/ftu3-panels.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu3-panels.png -------------------------------------------------------------------------------- /guided_b/files/ftu3-scene.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu3-scene.png -------------------------------------------------------------------------------- /guided_b/files/ftu3-top-toolbar.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu3-top-toolbar.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-caster_align.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-caster_align.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-caster_joint.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-caster_joint.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-caster_joint_ball.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-caster_joint_ball.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-caster_joint_z.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-caster_joint_z.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-caster_resize.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-caster_resize.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-caster_sphere.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-caster_sphere.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-chassis_height.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-chassis_height.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-chassis_scale.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-chassis_scale.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-copy_tool.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-copy_tool.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-depth_camera.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-depth_camera.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-depth_camera_joint.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-depth_camera_joint.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-depth_camera_joint_fixed.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-depth_camera_joint_fixed.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-depth_camera_translate.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-depth_camera_translate.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-editor_box.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-editor_box.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-exit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-exit.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-follow.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-follow.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-follower_plugin.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-follower_plugin.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-insert_tab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-insert_tab.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-joint_dialog.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-joint_dialog.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-model_database.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-model_database.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-model_plugin_inspector.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-model_plugin_inspector.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-model_plugin_inspector_done.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-model_plugin_inspector_done.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-model_tree.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-model_tree.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-save_as.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-save_as.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-scale_tool.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-scale_tool.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-snap_tool.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-snap_tool.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_align_x.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_align_x.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_align_y.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_align_y.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_align_y_reverse.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_align_y_reverse.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_castor_z.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_castor_z.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_joint.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_joint.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_joint_child.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_joint_child.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_joints.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_joints.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_paste.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_paste.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_pose_z.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_pose_z.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_rotate.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_rotate.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_rotation_axis.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_rotation_axis.png -------------------------------------------------------------------------------- /guided_b/files/ftu4-wheel_visual.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4-wheel_visual.png -------------------------------------------------------------------------------- /guided_b/files/ftu4_castor_sphere.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/ftu4_castor_sphere.png -------------------------------------------------------------------------------- /guided_b/files/gazebo8_model_editor_ui.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_b/files/gazebo8_model_editor_ui.png -------------------------------------------------------------------------------- /guided_b/tutorial5.md: -------------------------------------------------------------------------------- 1 | Stuff -------------------------------------------------------------------------------- /guided_b/tutorial6.md: -------------------------------------------------------------------------------- 1 | Stuff -------------------------------------------------------------------------------- /guided_b/tutorial7.md: -------------------------------------------------------------------------------- 1 | Content -------------------------------------------------------------------------------- /guided_b/tutorial8.md: -------------------------------------------------------------------------------- 1 | More content -------------------------------------------------------------------------------- /guided_b/tutorial9.md: -------------------------------------------------------------------------------- 1 | Content -------------------------------------------------------------------------------- /guided_i/files/blender_import.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/blender_import.png -------------------------------------------------------------------------------- /guided_i/files/blender_shrunk.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/blender_shrunk.png -------------------------------------------------------------------------------- /guided_i/files/blender_translate.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/blender_translate.png -------------------------------------------------------------------------------- /guided_i/files/box_no_noise.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/box_no_noise.jpg -------------------------------------------------------------------------------- /guided_i/files/freecad_base.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/freecad_base.png -------------------------------------------------------------------------------- /guided_i/files/topic_selector.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/topic_selector.png -------------------------------------------------------------------------------- /guided_i/files/velodyne_collisions.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_collisions.jpg -------------------------------------------------------------------------------- /guided_i/files/velodyne_complete_visual.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_complete_visual.jpg -------------------------------------------------------------------------------- /guided_i/files/velodyne_drawing.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_drawing.png -------------------------------------------------------------------------------- /guided_i/files/velodyne_hdl32.tar.gz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_hdl32.tar.gz -------------------------------------------------------------------------------- /guided_i/files/velodyne_inertia.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_inertia.jpg -------------------------------------------------------------------------------- /guided_i/files/velodyne_inertia_good.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_inertia_good.jpg -------------------------------------------------------------------------------- /guided_i/files/velodyne_insertion.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_insertion.png -------------------------------------------------------------------------------- /guided_i/files/velodyne_joint_cmd_widget.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_joint_cmd_widget.png -------------------------------------------------------------------------------- /guided_i/files/velodyne_joints.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_joints.jpg -------------------------------------------------------------------------------- /guided_i/files/velodyne_no_noise.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_no_noise.png -------------------------------------------------------------------------------- /guided_i/files/velodyne_noisy.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_noisy.png -------------------------------------------------------------------------------- /guided_i/files/velodyne_rays.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_rays.jpg -------------------------------------------------------------------------------- /guided_i/files/velodyne_top_visual_rotated.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_top_visual_rotated.jpg -------------------------------------------------------------------------------- /guided_i/files/velodyne_top_visual_unrotated.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_top_visual_unrotated.jpg -------------------------------------------------------------------------------- /guided_i/files/velodyne_vis_no_noise.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/guided_i/files/velodyne_vis_no_noise.png -------------------------------------------------------------------------------- /gzweb_development/tutorial_1.9.md: -------------------------------------------------------------------------------- 1 | # Overview 2 | 3 | The source code for Gzweb is located at the [osrf/gzweb](https://github.com/osrf/gzweb) GitHub repository. The source code is composed of two main parts: Javascript code inside `gzweb/gz3d`, responsible for visualization, and C++ code inside `gzweb/gzbridge`, responsible for communicating with `gzserver`. 4 | 5 | # Javascript development 6 | 7 | Gzweb makes use of the [JQuery mobile](http://jquerymobile.com/) user interface system for GUI and the [three.js](http://threejs.org/) library for 3D rendering. 8 | 9 | ## Grunt setup 10 | 11 | [Grunt](http://gruntjs.com/) is used for running tasks including code checking and minification: 12 | 13 | * Minification: Compresses all `*.js` code located at `gzweb/gz3d/src` into `gz3d.js` and `gz3d.min.js` files that can be included into other projects. 14 | * Code check: uses JSHint for detecting potential errors in Javascript code. 15 | 16 | To install required Grunt packages: 17 | 18 | npm install -g grunt-cli 19 | cd gz3d/utils && npm install 20 | 21 | ## Work Flow: 22 | 23 | 1. Make changes to Javascript source code at `gzweb/gz3d/src`. You may also edit files at `gzweb/gz3d/client/js/include`, but keep in mind most of these were taken from somewhere else. 24 | 25 | 1. Code check and minify Javascript files and copy them to the right directory, running: 26 | 27 | ./updateGZ3D.sh 28 | 29 | 1. Verify your changes: start gzweb with `./start_gzweb.sh` and open browser to `localhost:8080`, or just refresh page. If you don't see anything changed after modifying the Javascript code, you might need to clear your browser cache to see the changes. 30 | 31 | # C++ development 32 | 33 | Gzweb communicates with `gzserver` by publishing and subscribing to Gazebo topics. 34 | 35 | ## Work Flow: 36 | 37 | 1. Make changes to C++ source code in `gzweb/gzbridge` 38 | 39 | 1. You can compile by running: 40 | 41 | ./deploy.sh 42 | 43 | 1. Verify your changes: start gzweb with `./start_gzweb.sh` and open browser to `localhost:8080`, or just refresh page. 44 | 45 | # Making a contribution 46 | 47 | ## Bug reports and feature requests 48 | 49 | On Gzweb's [issue tracker](https://github.com/osrf/gzweb/issues), you're able to report bugs and ask for new features. Simply create an issue and categorize it accordingly. 50 | 51 | ## Pull requests 52 | 53 | If you've fixed a bug or added a feature and would like your changes to be integrated into Gzweb, you can make a [pull request](https://github.com/osrf/gzweb/pulls) to the repository, and the changes will be reviewed and merged. 54 | -------------------------------------------------------------------------------- /haptix_comm/files/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8 FATAL_ERROR) 2 | 3 | ######################################## 4 | # Find the haptix_comm library 5 | find_package(haptix-comm QUIET REQUIRED) 6 | if (NOT haptix-comm_FOUND) 7 | BUILD_ERROR ("Missing: Haptix Comm (libhaptix-comm-dev)") 8 | endif() 9 | 10 | set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${HAPTIX-COMM_CFLAGS}") 11 | include_directories(${HAPTIX-COMM_INCLUDE_DIRS}) 12 | link_directories(${HAPTIX-COMM_LIBRARY_DIRS}) 13 | 14 | ######################################## 15 | add_executable(hx_controller hx_controller.c) 16 | target_link_libraries(hx_controller ${HAPTIX-COMM_LIBRARIES} m) 17 | -------------------------------------------------------------------------------- /haptix_comm/files/visual-studio.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_comm/files/visual-studio.png -------------------------------------------------------------------------------- /haptix_install/files/gazebo_version.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_install/files/gazebo_version.png -------------------------------------------------------------------------------- /haptix_install/files/haptix_overview.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_install/files/haptix_overview.png -------------------------------------------------------------------------------- /haptix_install/files/haptix_version.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_install/files/haptix_version.png -------------------------------------------------------------------------------- /haptix_install/files/haptix_version2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_install/files/haptix_version2.png -------------------------------------------------------------------------------- /haptix_install/files/ifconfig.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_install/files/ifconfig.png -------------------------------------------------------------------------------- /haptix_install/files/ipconfig.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_install/files/ipconfig.png -------------------------------------------------------------------------------- /haptix_logging/files/logging_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_logging/files/logging_1.png -------------------------------------------------------------------------------- /haptix_logging/files/logging_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_logging/files/logging_2.png -------------------------------------------------------------------------------- /haptix_luke_hand/tutorial.md: -------------------------------------------------------------------------------- 1 | # Overview 2 | This tutorial describes how to install the DEKA Luke hand model and how to start 3 | the simulation environment with this limb. 4 | 5 | We assume that you have already completed the 6 | [installation step](/tutorials?tut=haptix_install&cat=haptix). 7 | 8 | ## Getting the DEKA Luke hand model and documentation 9 | 10 | All performer team leads should have received a download link 11 | for the DEKA Luke hand model from DEKA webtransfer system. 12 | If you believe you should have received a copy but did not, 13 | please contact `haptix@osrfoundation.org` for help. 14 | 15 | The model file will be provided in a zipped file that looks like 16 | `Luke_Hand_Gazebo_vXX.X.zip` with corresponding documentation file in 17 | another zip file named `Luke_Hand_Gazebo_Doc_vXX.X.zip`. 18 | 19 | Note that the generic haptix and simulation API documentation can be found 20 | [here](http://gazebosim.org/haptix/api). 21 | 22 | ### Installing Gazebo DEKA Luke hand model for handsim 23 | 24 | ~~~ 25 | unzip Luke_Hand_Gazebo_vX.X.zip -d ~/.gazebo/models/ 26 | ~~~ 27 | 28 | ### Installing documentation for Gazebo DEKA Luke hand model 29 | 30 | ~~~ 31 | unzip Luke_Hand_Gazebo_Doc_vX.X.zip -d /tmp/ 32 | ~~~ 33 | 34 | To view documentation, open the following link in a browser: 35 | 36 | [file:///tmp/haptix_wiki/haptix/index.html](file:///tmp/haptix_wiki/haptix/index.html) 37 | 38 | ## Running handsim with DEKA Luke hand model 39 | 40 | To start Gazebo with the DEKA Luke hand model, type the following command 41 | in a terminal: 42 | 43 | ~~~ 44 | gazebo --verbose worlds/luke_hand.world 45 | ~~~ 46 | -------------------------------------------------------------------------------- /haptix_matlab/files/matlab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_matlab/files/matlab.png -------------------------------------------------------------------------------- /haptix_optitrack/files/arm_alignment.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/arm_alignment.png -------------------------------------------------------------------------------- /haptix_optitrack/files/armcloseup.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/armcloseup.png -------------------------------------------------------------------------------- /haptix_optitrack/files/camera_preview.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/camera_preview.PNG -------------------------------------------------------------------------------- /haptix_optitrack/files/data_streaming.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/data_streaming.PNG -------------------------------------------------------------------------------- /haptix_optitrack/files/diy_target.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/diy_target.png -------------------------------------------------------------------------------- /haptix_optitrack/files/fullsetup.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/fullsetup.png -------------------------------------------------------------------------------- /haptix_optitrack/files/groundplane.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/groundplane.PNG -------------------------------------------------------------------------------- /haptix_optitrack/files/haptix_osrf.ttp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/haptix_osrf.ttp -------------------------------------------------------------------------------- /haptix_optitrack/files/head_alignment.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/head_alignment.png -------------------------------------------------------------------------------- /haptix_optitrack/files/monitor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/monitor.png -------------------------------------------------------------------------------- /haptix_optitrack/files/motive_icon.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/motive_icon.PNG -------------------------------------------------------------------------------- /haptix_optitrack/files/motive_start.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/motive_start.PNG -------------------------------------------------------------------------------- /haptix_optitrack/files/new_rigid_body.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/new_rigid_body.PNG -------------------------------------------------------------------------------- /haptix_optitrack/files/perspective_view.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/perspective_view.PNG -------------------------------------------------------------------------------- /haptix_optitrack/files/premade_trackers.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/premade_trackers.png -------------------------------------------------------------------------------- /haptix_optitrack/files/selection.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/selection.PNG -------------------------------------------------------------------------------- /haptix_optitrack/files/spheres.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_optitrack/files/spheres.png -------------------------------------------------------------------------------- /haptix_tactors/files/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8 FATAL_ERROR) 2 | 3 | ######################################## 4 | # Find the haptix-comm library 5 | find_package(haptix-comm QUIET REQUIRED) 6 | if (NOT haptix-comm_FOUND) 7 | BUILD_ERROR ("Missing: Haptix Comm (libhaptix-comm-dev)") 8 | endif() 9 | 10 | set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${HAPTIX-COMM_CFLAGS}") 11 | include_directories(${HAPTIX-COMM_INCLUDE_DIRS}) 12 | link_directories(${HAPTIX-COMM_LIBRARY_DIRS}) 13 | 14 | ######################################## 15 | # Find the Ignition_Transport library 16 | find_package(ignition-transport QUIET REQUIRED) 17 | set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${IGNITION-TRANSPORT_CXX_FLAGS}") 18 | 19 | include_directories(${IGNITION-TRANSPORT_INCLUDE_DIRS}) 20 | link_directories(${IGNITION-TRANSPORT_LIBRARY_DIRS}) 21 | 22 | ######################################## 23 | # The Google Protobuf library 24 | find_package(Protobuf REQUIRED) 25 | if (NOT PROTOBUF_FOUND) 26 | BUILD_ERROR ("Missing: Google Protobuf (libprotobuf-dev)") 27 | endif() 28 | if (NOT PROTOBUF_PROTOC_EXECUTABLE) 29 | BUILD_ERROR ("Missing: Google Protobuf Compiler (protobuf-compiler)") 30 | endif() 31 | if (NOT PROTOBUF_PROTOC_LIBRARY) 32 | BUILD_ERROR ("Missing: Google Protobuf Compiler Library (libprotoc-dev)") 33 | endif() 34 | ######################################## 35 | 36 | add_executable(tactors tactors.cc) 37 | target_link_libraries(tactors ${HAPTIX-COMM_LIBRARIES} ${IGNITION-TRANSPORT_LIBRARIES} ${PROTOBUF_LIBRARY} ${EXTRA_LIBRARIES}) 38 | -------------------------------------------------------------------------------- /haptix_tactors/files/arduino_sketch.c: -------------------------------------------------------------------------------- 1 | // Arduino sketch for tactor glove 2 | // Author: Morgan Quigley 3 | // pinout: https://www.pjrc.com/teensy/card2b.pdf 4 | 5 | #define NUM_MOTORS 5 6 | #define MOTOR_RUN_TIME 100 7 | #define MOTOR_PWM 255 8 | int led = 11; 9 | int motors[NUM_MOTORS] = {4, 9, 10, 12, 14}; 10 | unsigned long t_motor_start[NUM_MOTORS] = { 0, 0, 0, 0, 0 }; 11 | 12 | void setup() 13 | { 14 | pinMode(led, OUTPUT); 15 | for (int i = 0; i < NUM_MOTORS; i++) 16 | { 17 | pinMode(motors[i], OUTPUT); 18 | analogWrite(motors[i], 0); 19 | } 20 | Serial.begin(9600); // baud rate is ignored on teensy... it's usb, 21 | baudrate is ignored... 22 | } 23 | 24 | void loop() 25 | { 26 | for (int i = 0; i < NUM_MOTORS; i++) 27 | { 28 | if (!t_motor_start[i]) 29 | continue; // motor isn't running 30 | if (millis() > t_motor_start[i] + MOTOR_RUN_TIME) 31 | { 32 | analogWrite(motors[i], 0); 33 | t_motor_start[i] = 0; 34 | } 35 | } 36 | 37 | if (Serial.available()) 38 | { 39 | char b = Serial.read(); 40 | if (b >= '1' && b <= '5') 41 | { 42 | int motor = b - '1'; 43 | t_motor_start[motor] = millis(); 44 | analogWrite(motors[motor], MOTOR_PWM); 45 | } 46 | } 47 | } 48 | -------------------------------------------------------------------------------- /haptix_tactors/files/glove_back.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_tactors/files/glove_back.jpg -------------------------------------------------------------------------------- /haptix_tactors/files/glove_front.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_tactors/files/glove_front.jpg -------------------------------------------------------------------------------- /haptix_tactors/files/grasp_sim.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_tactors/files/grasp_sim.png -------------------------------------------------------------------------------- /haptix_tactors/files/tactors_soldered.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_tactors/files/tactors_soldered.jpg -------------------------------------------------------------------------------- /haptix_tactors/files/teensy_pinout.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_tactors/files/teensy_pinout.png -------------------------------------------------------------------------------- /haptix_teleop/files/gui_teleop.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_teleop/files/gui_teleop.png -------------------------------------------------------------------------------- /haptix_teleop/files/keyboard.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_teleop/files/keyboard.png -------------------------------------------------------------------------------- /haptix_unboxing/files/desktop.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/haptix_unboxing/files/desktop.png -------------------------------------------------------------------------------- /haptix_world_sim_api/files/custom_world.m: -------------------------------------------------------------------------------- 1 | % test program that changes color of a sphere when it comes into contact 2 | % with other objects (e.g. hand) 3 | 4 | 5 | hxs_set_model_collide_mode('sphere_visual_model', 1); 6 | pose = hxs_model_transform('sphere_visual_model'); 7 | 8 | while (true) 9 | % note that the color vector is defined by the RGBA 4-tuple: 10 | % 11 | % https://s3.amazonaws.com/osrf-distributions/haptix/api/0.7.1/struct__hxsColor.html 12 | % 13 | % The elements are ordered such that: 14 | % color(1) = float value for the red component 15 | % color(2) = float value for the green component 16 | % color(3) = float value for the blue component 17 | % color(4) = float value for the alpha component 18 | % 19 | color = [0;1;0;1]; 20 | if length(hxs_contacts('sphere_visual_model')) > 0, 21 | color = [1;0;0;1]; 22 | end, 23 | hxs_set_model_color('sphere_visual_model', color); 24 | 25 | % move sphere around 26 | t = hx_read_sensors().time_stamp; 27 | p = pose; 28 | p.pos(1) = pose.pos(1) - 0.2*cos(1*t); 29 | hxs_set_model_transform('sphere_visual_model', p); 30 | 31 | sleep(0.001); 32 | endwhile 33 | -------------------------------------------------------------------------------- /hydra_gzjs_pub/tutorial.md: -------------------------------------------------------------------------------- 1 | # Introduction 2 | 3 | Hydra publisher using GazeboJs and node-sixense modules. It publishes the hydra messages over the `~/hydra` gazebo topic. Similar tutorial cand be found [here](http://www.gazebosim.org/tutorials?tut=hydra&cat=user_input). The main difference being that the later requires gazebo being installed from source. 4 | 5 | ## Project setup 6 | 7 | Make sure gazebo is running 8 | 9 | gazebo 10 | 11 | Install the publisher: 12 | 13 | npm install hydra_gzjs_pub 14 | 15 | Run the publisher: 16 | 17 | cd node_modules/hydra_gzjs_pub 18 | sudo node hydra_pub.js 19 | 20 | For publishing the hydra controller without root privileges please look at [this](http://www.gazebosim.org/tutorials?tut=hydra&cat=user_input) tutorial. 21 | 22 | Test that the publisher works: 23 | 24 | gz topic -l 25 | gz topic -e /gazebo/default/hydra 26 | 27 | 28 | ### Code 29 | The publisher code is located in the hydra_pub.js file 30 | 31 | ([hydra_pub.js](https://bitbucket.org/ahaidu/hydra_gzjs_pub/raw/master/hydra_pub.js)): 32 | 33 | 34 | 35 | 36 | ### Code explained 37 | 38 | The first lines load the Gazebo C++ and the node-sixense modules into the Node V8 script engine, and creates and instance of the Gazebo class. 39 | 40 | ~~~ 41 | var hydra = require('node-sixense'); 42 | var gazebojs = require('gazebojs'); 43 | var gazebo = new gazebojs.Gazebo(); 44 | ~~~ 45 | 46 | We then set the message type and the topic: 47 | 48 | ~~~ 49 | var type = "gazebo.msgs.Hydra" 50 | var topic = "~/hydra" 51 | ~~~ 52 | 53 | We then initialize sixense and for every new data we call the `sixenseGetAllNewestDataAsync` callback function which publishes the hydra message. 54 | 55 | ~~~ 56 | hydra.sixenseInit(); 57 | hydra.sixenseSetActiveBase(0); 58 | hydra.sixenseGetAllNewestDataAsync(function (error, allData) 59 | { 60 | var msgS = 61 | ~~~ 62 | 63 | ... 64 | 65 | ~~~ 66 | var msg = JSON.parse(msgS); 67 | gazebo.publish(type, topic , msg); 68 | }); 69 | ~~~ 70 | 71 | ### Troubleshooting 72 | 73 | In case of offsets, the axis of the controller have been switched in multiple places in order to be similar to the output of the hydra [plugin](http://www.gazebosim.org/tutorials?tut=hydra&cat=user_input) version. If needed otherwise these can be easily changed from the source code. 74 | 75 | 76 | 77 | 78 | -------------------------------------------------------------------------------- /hydrodynamics/files/leftmenu.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/hydrodynamics/files/leftmenu.png -------------------------------------------------------------------------------- /hydrodynamics/files/submarines.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/hydrodynamics/files/submarines.png -------------------------------------------------------------------------------- /import_mesh/files/TutorialMeshDuck.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/import_mesh/files/TutorialMeshDuck.png -------------------------------------------------------------------------------- /import_mesh/files/my_mesh.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | model://ground_plane 6 | 7 | 8 | model://sun 9 | 10 | 11 | 0 0 0 0 0 0 12 | true 13 | 14 | 15 | 16 | file://my_mesh.dae 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /import_mesh/tutorial.md: -------------------------------------------------------------------------------- 1 | This tutorial describes how to import 3D meshes into Gazebo. 2 | 3 | # Prepare the Mesh 4 | 5 | Gazebo uses a right-hand coordinate system where +Z is up (vertical), +X is forward (into the screen), and +Y is to the left. 6 | 7 | **Reduce Complexity** 8 | 9 | Many meshes can be overly complex. A mesh with many thousands of triangles should be reduced or split into separate meshes for efficiency. Look at the documentation of your 3D mesh editor for information about reducing triangle count or splitting up a mesh. 10 | 11 | **Center the mesh** 12 | 13 | The first step is to center the mesh at (0,0,0) and orient the front (which can be subjective) along the x-axis. 14 | 15 | **Scale the mesh** 16 | 17 | Gazebo uses the metric system. Many meshes (especially those from 3D warehouse), use English units. Use your favorite 3D editor to scale the mesh to a metric size. 18 | 19 | # Export the Mesh ### 20 | 21 | Once the mesh has been properly prepared, export it as a Collada file. This format will contain all the 3D information and the materials. 22 | 23 | # Test the Mesh ### 24 | 25 | The easiest way to test a mesh is to create a simple world file [my_mesh.world](http://github.com/osrf/gazebo_tutorials/raw/master/import_mesh/files/my_mesh.world) that loads the mesh. Replace `my_mesh.dae` with the actual filename of the mesh. 26 | 27 | 28 | 29 | Then just launch Gazebo in the directory where is the file: 30 | 31 | ~~~ 32 | gazebo my_mesh.world 33 | ~~~ 34 | 35 | # Test Mesh ### 36 | 37 | You can use these [duck.dae](https://web.archive.org/web/20120513213905/http://www.c3dl.org/wp-content/2.0Release/Resources/duck.dae) and [duck.png](https://web.archive.org/web/20120513213905/http://www.c3dl.org/wp-content/2.0Release/Resources/duck.png) mesh files. Put them together in the same directory as the world file. Since the duck mesh is defined with the y-axis as up, you can put a rotation in the sdf so that it displays upright: 38 | 39 | ~~~ 40 | 41 | 0 0 0 1.5708 0 0 42 | 43 | file://duck.dae 44 | 45 | 46 | ~~~ 47 | 48 | [[file:files/TutorialMeshDuck.png|640px]] 49 | -------------------------------------------------------------------------------- /inertia/files/gazebo_inertia.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/inertia/files/gazebo_inertia.jpg -------------------------------------------------------------------------------- /inertia/files/meshlab.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/inertia/files/meshlab.jpg -------------------------------------------------------------------------------- /install_on_mac/tutorial_11-0.md: -------------------------------------------------------------------------------- 1 | # Install Gazebo on Mac (using homebrew) 2 | 3 | Gazebo and several of its dependencies can be compiled on OS X with 4 | [Homebrew](http://brew.sh) using the 5 | [osrf/simulation tap](https://github.com/osrf/homebrew-simulation). 6 | Gazebo is straightforward to install on Mac OS X 10.11 (El Capitan) or higher. 7 | Installation on older versions requires changing the default standard library 8 | and rebuilding dependencies due to the 9 | [use of c++11](https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-requests/1340). 10 | For purposes of this tutorial, I will assume OS X 10.11 or greater is in use. 11 | 12 | ## Default installation: one-liner 13 | 14 | 1. Install 15 | 16 | curl -ssL http://get.gazebosim.org | sh 17 | 18 | 2. Run 19 | 20 | gazebo 21 | 22 | ## Alternative installation: step-by-step 23 | 24 | 1. Install [homebrew](http://brew.sh), which should also prompt you to install 25 | the XCode command-line tools: 26 | 27 | ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)" 28 | 29 | 2. Install [XQuartz](http://xquartz.macosforge.org/landing/), which provides 30 | X11 support and is required by Gazebo and OGRE 31 | 32 | 3. Run the following commands to install gazebo quickly with a precompiled binary: 33 | 34 | brew tap osrf/simulation 35 | brew install gazebo11 36 | gazebo 37 | 38 | ## Versions 39 | The formula currently installs version 11.0 of Gazebo. Version 9 can be 40 | installed using the `gazebo9`. To install the latest version of Gazebo11 from 41 | gazebo11 development branch: 42 | 43 | brew install gazebo11 --HEAD 44 | -------------------------------------------------------------------------------- /install_on_mac/tutorial_9-0.md: -------------------------------------------------------------------------------- 1 | # Install Gazebo on Mac (using homebrew) 2 | 3 | Gazebo and several of its dependencies can be compiled on OS X with 4 | [Homebrew](http://brew.sh) using the 5 | [osrf/simulation tap](https://github.com/osrf/homebrew-simulation). 6 | Gazebo is straightforward to install on Mac OS X 10.11 (El Capitan) or higher. 7 | Installation on older versions requires changing the default standard library 8 | and rebuilding dependencies due to the 9 | [use of c++11](https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-requests/1340/). 10 | For purposes of this tutorial, I will assume OS X 10.11 or greater is in use. 11 | 12 | ## Default installation: one-liner 13 | 14 | 1. Install 15 | 16 | curl -ssL http://get.gazebosim.org | sh 17 | 18 | 2. Run 19 | 20 | gazebo 21 | 22 | ## Alternative installation: step-by-step 23 | 24 | 1. Install [homebrew](http://brew.sh), which should also prompt you to install 25 | the XCode command-line tools: 26 | 27 | ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)" 28 | 29 | 2. Install [XQuartz](http://xquartz.macosforge.org/landing/), which provides 30 | X11 support and is required by Gazebo and OGRE 31 | 32 | 3. Run the following commands to install gazebo quickly with a precompiled binary: 33 | 34 | brew tap osrf/simulation 35 | brew install gazebo9 36 | gazebo 37 | -------------------------------------------------------------------------------- /instrument_hdf5_datasets/files/hdf5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/instrument_hdf5_datasets/files/hdf5.png -------------------------------------------------------------------------------- /instrument_hdf5_datasets/tutorial.md: -------------------------------------------------------------------------------- 1 | # Introduction 2 | 3 | Instrument tools are provided to dump physical data into [HDF5](https://www.hdfgroup.org/HDF5/) 4 | format. The datasets, together with 5 | the [Benchmark Problems for Multibody Dynamis (BPMD)](https://grasp.robotics.cs.rpi.edu/bpmd/) 6 | framework are used to compare different methods in solving multibody systems with bilateral 7 | joints and unilateral frictional contacts in an unbiased way. These datasets will help researchers 8 | to concentrate on analysis of existing methods and construction of more accurate solvers, 9 | without worrying about implementation of the whole physics engine. 10 | 11 | # Example Usage 12 | 13 | ## Install hdf5 14 | ~~~ 15 | sudo apt-get install libhdf5-dev 16 | ~~~ 17 | 18 | ## Build Gazebo 19 | This HDF5 instrument tool requires building Gazebo from source, with the cmake parameter 20 | `HDF5_INSTRUMENT` [default False] as True. 21 | [Learn how to build Gazebo from source](/tutorials?tut=install_from_source&cat=install) 22 | 23 | cd ~/gazebo 24 | mkdir build 25 | cd build 26 | cmake -DHDF5_INSTRUMENT=True ../ 27 | make -j4 28 | sudo make install 29 | 30 | ## Collect Datasets 31 | ### Use only gzserver 32 | 33 | ~~~ 34 | ./test/integration/INTEGRATION_physics_inertia_ratio 35 | ~~~ 36 | 37 | ### Use the world file 38 | 39 | ~~~ 40 | gazebo ~/gazebo/worlds/friction_demo.world 41 | ~~~ 42 | 43 | 44 | Then a file named `ode_frames.hdf5` will be generated at the directory exactly where the 45 | above command is run. 46 | 47 | ## View the HDF5 file 48 | 49 | hdfvivew is used to open the hdf5 files. You can install it via the terminal: 50 | 51 | ~~~ 52 | sudo apt-get install hdfview 53 | ~~~ 54 | 55 | Then open the stored file with: 56 | 57 | ~~~ 58 | hdfview ode_frames.hdf5 59 | ~~~ 60 | 61 | A hierarchical file shows up: 62 | 63 | [[file:files/hdf5.png|800px]] 64 | 65 | 66 | **Note**: The instrument tool will save hierarchical data for each time step, so it will be 67 | slow to write the data into the `ode_frames.hdf5` file. 68 | Be patient, especially for complex simulation scenarios such as Atlas robots or many body simulation. 69 | 70 | 71 | 72 | -------------------------------------------------------------------------------- /introspection/files/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8 FATAL_ERROR) 2 | 3 | # Find Gazebo 4 | find_package(gazebo REQUIRED) 5 | include_directories(${GAZEBO_INCLUDE_DIRS}) 6 | link_directories(${GAZEBO_LIBRARY_DIRS}) 7 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") 8 | 9 | # Find the Ignition_Transport library 10 | find_package(ignition-transport2 QUIET) 11 | if (NOT ignition-transport2_FOUND) 12 | find_package(ignition-transport1 REQUIRED) 13 | endif() 14 | set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${IGNITION-TRANSPORT_CXX_FLAGS}") 15 | include_directories(${IGNITION-TRANSPORT_INCLUDE_DIRS}) 16 | link_directories(${IGNITION-TRANSPORT_LIBRARY_DIRS}) 17 | 18 | add_library(introspectable_plugin SHARED introspectable_plugin.cc) 19 | target_link_libraries(introspectable_plugin ${GAZEBO_LIBRARIES}) 20 | 21 | add_executable(watcher watcher.cc) 22 | target_link_libraries(watcher ${GAZEBO_LIBRARIES} ${IGNITION-TRANSPORT_LIBRARIES}) 23 | -------------------------------------------------------------------------------- /introspection/files/empty.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | model://ground_plane 8 | 9 | 10 | 11 | model://sun 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /introspection/files/introspectable_plugin.cc: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | namespace gazebo 8 | { 9 | class ModelPush : public WorldPlugin 10 | { 11 | public: void Load(physics::WorldPtr _parent, sdf::ElementPtr /*_sdf*/) 12 | { 13 | // Listen to the update event. This event is broadcast every 14 | // simulation iteration. 15 | this->updateConnection = event::Events::ConnectWorldUpdateBegin( 16 | std::bind(&ModelPush::OnUpdate, this)); 17 | 18 | // Introspection callback. 19 | auto fCounterValue = [this]() 20 | { 21 | return this->counter; 22 | }; 23 | 24 | // Register the counter element. 25 | gazebo::util::IntrospectionManager::Instance()->Register( 26 | "data://my_plugin/counter", fCounterValue); 27 | } 28 | 29 | // Called by the world update start event. 30 | public: void OnUpdate() 31 | { 32 | ++this->counter; 33 | } 34 | 35 | // Pointer to the update event connection. 36 | private: event::ConnectionPtr updateConnection; 37 | 38 | // A counter for testing the introspection capabilites. 39 | private: int counter = 0; 40 | }; 41 | 42 | // Register this plugin with the simulator. 43 | GZ_REGISTER_WORLD_PLUGIN(ModelPush) 44 | } 45 | -------------------------------------------------------------------------------- /introspection/files/introspection_registration.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/introspection/files/introspection_registration.png -------------------------------------------------------------------------------- /introspection/files/introspection_subscription.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/introspection/files/introspection_subscription.png -------------------------------------------------------------------------------- /introspection/files/readme: -------------------------------------------------------------------------------- 1 | The figures can be edited using https://www.draw.io 2 | -------------------------------------------------------------------------------- /introspection/files/watcher.cc: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | ///////////////////////////////////////////////// 10 | void cb(const gazebo::msgs::Param_V &_msg) 11 | { 12 | std::cout << _msg.DebugString() << std::endl; 13 | } 14 | 15 | ////////////////////////////////////////////////// 16 | int main(int argc, char **argv) 17 | { 18 | // Use the introspection service for finding the "sim_time" and "counter" 19 | // items. 20 | gazebo::util::IntrospectionClient client; 21 | 22 | // Wait for the managers to come online. 23 | std::set managerIds = client.WaitForManagers( 24 | std::chrono::seconds(2)); 25 | 26 | if (managerIds.empty()) 27 | { 28 | std::cerr << "No introspection managers detected." << std::endl; 29 | std::cerr << "Is a gzserver running?" << std::endl; 30 | return -1; 31 | } 32 | 33 | // Pick up the first manager. 34 | std::string managerId = *managerIds.begin(); 35 | 36 | // sim_time is a pre-registered item with the following URI format: 37 | // data://world/?p=/ 38 | std::string simTime = "data://world/default?p=time/sim_time"; 39 | std::string counter = "data://my_plugin/counter"; 40 | 41 | // Check if "sim_time" is registered. 42 | if (!client.IsRegistered(managerId, simTime)) 43 | { 44 | std::cerr << "The sim_time item is not registered on the manager.\n"; 45 | return -1; 46 | } 47 | 48 | // Check if "counter" is registered. 49 | if (!client.IsRegistered(managerId, counter)) 50 | { 51 | std::cerr << "The counter item is not registered on the manager.\n"; 52 | return -1; 53 | } 54 | 55 | // The variables to watch are registered with the manager 56 | 57 | // Create a filter for watching the items. 58 | std::string filterId, topic; 59 | if (!client.NewFilter(managerId, {simTime, counter}, filterId, topic)) 60 | return -1; 61 | 62 | // Let's subscribe to the topic for receiving updates. 63 | ignition::transport::Node node; 64 | node.Subscribe(topic, cb); 65 | 66 | // zZZZ. 67 | ignition::transport::waitForShutdown(); 68 | 69 | return 0; 70 | } 71 | -------------------------------------------------------------------------------- /joint_events/apply_force.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/joint_events/apply_force.png -------------------------------------------------------------------------------- /joint_events/apply_force_torque.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/joint_events/apply_force_torque.png -------------------------------------------------------------------------------- /joint_events/joint_test_world.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/joint_events/joint_test_world.png -------------------------------------------------------------------------------- /joint_events/select_needle_link.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/joint_events/select_needle_link.png -------------------------------------------------------------------------------- /joint_events/sim_event_topic_response.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/joint_events/sim_event_topic_response.png -------------------------------------------------------------------------------- /joint_events/topic_visualizer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/joint_events/topic_visualizer.png -------------------------------------------------------------------------------- /joint_events/torque_needle.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/joint_events/torque_needle.png -------------------------------------------------------------------------------- /kinematic_loop/four_bar.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/kinematic_loop/four_bar.png -------------------------------------------------------------------------------- /kinematic_loop/four_bar_sdf/README.md: -------------------------------------------------------------------------------- 1 | To regenerate the model.sdf from the erb template: 2 | 3 | ~~~ 4 | erb -T 1 model.sdf.erb > model.sdf 5 | ~~~ 6 | 7 | -------------------------------------------------------------------------------- /kinematic_loop/four_bar_sdf/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Four-bar linkage in SDF 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Steve Peters 10 | scpeters@osrfoundation.org 11 | 12 | 13 | 14 | Four-bar linkage in modeled in SDFormat. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /kinematic_loop/four_bar_split.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/kinematic_loop/four_bar_split.png -------------------------------------------------------------------------------- /kinematic_loop/four_bar_split_fixed_sdf/README.md: -------------------------------------------------------------------------------- 1 | To regenerate the model.sdf from the erb template: 2 | 3 | ~~~ 4 | erb -T 1 model.sdf.erb > model.sdf 5 | ~~~ 6 | 7 | -------------------------------------------------------------------------------- /kinematic_loop/four_bar_split_fixed_sdf/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Four-bar linkage in SDF with split link and fixed joint 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Steve Peters 10 | scpeters@osrfoundation.org 11 | 12 | 13 | 14 | Four-bar linkage in modeled in SDFormat. 15 | One of the links is split in half and re-connected with a fixed joint. 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /kinematic_loop/four_bar_split_fixed_urdf/README.md: -------------------------------------------------------------------------------- 1 | To regenerate the model.urdf from the erb template: 2 | 3 | ~~~ 4 | erb -T 1 model.urdf.erb > model.urdf 5 | ~~~ 6 | 7 | -------------------------------------------------------------------------------- /kinematic_loop/four_bar_split_fixed_urdf/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Four-bar linkage in URDF with split link and fixed joint 5 | 1.0 6 | model.urdf 7 | 8 | 9 | Steve Peters 10 | scpeters@osrfoundation.org 11 | 12 | 13 | 14 | Four-bar linkage in modeled in URDF. 15 | One of the links is split in half and re-connected with a fixed joint. 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /led_plugin/files/LED.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/led_plugin/files/LED.png -------------------------------------------------------------------------------- /led_plugin/files/example.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/led_plugin/files/example.gif -------------------------------------------------------------------------------- /led_plugin/tutorial_9-3.md: -------------------------------------------------------------------------------- 1 | # Introduction 2 | 3 | [[file:files/example.gif|640px]] 4 | 5 | LedPlugin is a [model plugin](/tutorials?tut=plugins_model&cat=write_plugin) included with gazebo that synchronously flashes and dims light and visual objects on a model. By giving parameters to the plugin, you can choose which lights and visuals to blink, and you can also specify the duration and interval time of flashing for each of lights. By inheriting this plugin, you can also use internal features, e.g., dynamically turning the lights on/off. 6 | 7 | # Usage and Plugin Parameters 8 | Insert your plugin block with the `filename` attribute set to `libLedPlugin.so` within the `` element. In the following example (the world file is available [here](https://github.com/osrf/gazebo/raw/gazebo9/worlds/led_plugin_demo.world)), the model has two links each of which has two light elements. 9 | 10 | This plugin inherits from [FlashLightPlugin](/tutorials?tut=flashlight_plugin&cat=plugins), so it takes the same parameters as the base plugin does. The difference is that, when you place a `` object with the name of the `` object under the same `` object, it will blink at the same timing. 11 | 12 | ```XML 13 | 14 | 15 | ... 16 | 17 | 18 | 19 | ... 20 | 21 | 22 | ... 23 | 24 | 25 | 26 | ... 27 | 28 | 29 | ... 30 | 31 | 32 | 33 | ... 34 | 35 | 36 | 37 | link/lamp 38 | 0.5 39 | 0.5 40 | 41 | 42 | ... 43 | 44 | 45 | 46 | ``` 47 | 48 | # Implementation Details 49 | The diagram below shows an abstract structure of the plugin and its components. 50 | `LedPlugin` class holds `LedSetting` objects, each of which holds a unit of settings and maintains the corresponding light element by the Gazebo transport topic. `LedPlugin` and `LedSetting` are child classes of `FlashLightPlugin` and `FlashLightSetting` respectively so they have the functionalities of the base classes. 51 | 52 | [[file:files/LED.png|640px]] 53 | 54 | They send messages to the topic `~/visual` to update the specified `` objects. As `Flash()` and `Dim()` are called, `LedSetting()` publishes a message to this topic. 55 | -------------------------------------------------------------------------------- /lightmap/table_lightmap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/lightmap/table_lightmap.png -------------------------------------------------------------------------------- /lightmap/table_no_lighting.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/lightmap/table_no_lighting.png -------------------------------------------------------------------------------- /lightmap/table_no_lightmap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/lightmap/table_no_lightmap.png -------------------------------------------------------------------------------- /lockstep_physics_sensors/files/lockstep_highres_camera.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/lockstep_physics_sensors/files/lockstep_highres_camera.png -------------------------------------------------------------------------------- /lockstep_physics_sensors/files/lockstep_regular_camera.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/lockstep_physics_sensors/files/lockstep_regular_camera.png -------------------------------------------------------------------------------- /lockstep_physics_sensors/files/no_lockstep.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/lockstep_physics_sensors/files/no_lockstep.png -------------------------------------------------------------------------------- /lockstep_physics_sensors/files/topic_selector.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/lockstep_physics_sensors/files/topic_selector.png -------------------------------------------------------------------------------- /logging_playback/files/data_logger.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/logging_playback/files/data_logger.png -------------------------------------------------------------------------------- /logging_playback/files/playback_gui.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/logging_playback/files/playback_gui.png -------------------------------------------------------------------------------- /logging_playback/files/recordings.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/logging_playback/files/recordings.png -------------------------------------------------------------------------------- /logical_camera_sensor/files/tutorial_logical_camera.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | model://sun 6 | 7 | 8 | 9 | 0 0 1 0 0 3.14159 10 | true 11 | 12 | 13 | 14 | 0.55 15 | 2.5 16 | 1.05 17 | 1.8 18 | 19 | 20 | true 21 | true 22 | 10 23 | 24 | 25 | 26 | 27 | 28 | true 29 | -2 0 1 0 0 0 30 | 31 | 32 | 33 | 34 | 1 1 1 35 | 36 | 37 | 38 | 39 | 40 | 41 | 1 1 1 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | -------------------------------------------------------------------------------- /logical_camera_sensor/files/tutorial_logical_camera.world.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/logical_camera_sensor/files/tutorial_logical_camera.world.png -------------------------------------------------------------------------------- /logical_camera_sensor/files/tutorial_logical_camera_aabb_false_positive.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | model://sun 6 | 7 | 8 | 9 | 0 0 1 0 0 0.707 10 | true 11 | 12 | 13 | 14 | 0.55 15 | 2.5 16 | 1.05 17 | 1.8 18 | 19 | 20 | true 21 | true 22 | 10 23 | 24 | 25 | 26 | 27 | 28 | true 29 | 0.25 2.9 0 0 0 0 30 | 31 | 0 0 0 0 0 0.707 32 | 33 | 34 | 35 | 1 1 2 36 | 37 | 38 | 39 | 40 | 41 | 42 | 1 1 2 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 1.41 1.41 2 53 | 54 | 55 | 56 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | -------------------------------------------------------------------------------- /logical_camera_sensor/files/tutorial_logical_camera_aabb_false_positive.world.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/logical_camera_sensor/files/tutorial_logical_camera_aabb_false_positive.world.png -------------------------------------------------------------------------------- /logical_camera_sensor/files/wireframe.material: -------------------------------------------------------------------------------- 1 | material Wireframe/Purple 2 | { 3 | technique 4 | { 5 | pass ambient 6 | { 7 | ambient 1 0 1 8 | diffuse 1 0 1 9 | specular 0.1 0.1 0.1 1 1 10 | polygon_mode wireframe 11 | cull_hardware none 12 | cull_software none 13 | } 14 | } 15 | } 16 | -------------------------------------------------------------------------------- /manifest_to_tsv.rb: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env ruby 2 | 3 | require 'rexml/document' 4 | 5 | xmlInput = File.read("manifest.xml") 6 | 7 | doc, categories = REXML::Document.new(xmlInput), [] 8 | 9 | # parse list of categories 10 | doc.elements.each("content/categories/category") do |e| 11 | c = {:ref => e.attributes["ref"], :title => e.attributes["title"], :tutorials => []} 12 | e.elements.each("tutorials/tutorial") do |t| 13 | c[:tutorials] << t.text 14 | end 15 | categories << c 16 | end 17 | 18 | # print csv for each category 19 | rows_per_tutorial = 3 20 | categories.each do |c| 21 | puts c[:title] 22 | puts "Tutorial name\tAssigned to\tIssues\tSolution\tApproved?\t\OS / Build type" 23 | c[:tutorials].each do |t| 24 | rows_per_tutorial.times do 25 | puts "=HYPERLINK(\"http://gazebosim.org/tutorials?tut=#{t}&cat=#{c[:ref]}\",\"#{t}\")" 26 | end 27 | end 28 | end 29 | -------------------------------------------------------------------------------- /model_editor/files/empty_editor.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/empty_editor.png -------------------------------------------------------------------------------- /model_editor/files/empty_editor_7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/empty_editor_7.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_car.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_car.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_car_done.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_car_done.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_edit_name.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_edit_name.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_existing_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_existing_model.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_insert_mesh.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_insert_mesh.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_insert_mesh_7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_insert_mesh_7.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_insert_mesh_8.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_insert_mesh_8.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_inspector.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_inspector.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_inspector_7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_inspector_7.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_joint.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_joint.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_joint_7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_joint_7.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_joint_inspector.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_joint_inspector.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_joint_inspector_7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_joint_inspector_7.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_save_dialog.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_save_dialog.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_save_dialog_7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_save_dialog_7.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_simple_shapes.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_simple_shapes.png -------------------------------------------------------------------------------- /model_editor/files/model_editor_simple_shapes_7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/model_editor_simple_shapes_7.png -------------------------------------------------------------------------------- /model_editor/files/undo_redo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_editor/files/undo_redo.png -------------------------------------------------------------------------------- /model_population/files/can_population.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | model://sun 8 | 9 | 10 | 11 | 12 | model://ground_plane 13 | 14 | 15 | 16 | 17 | 18 | 19 | true 20 | model://coke_can 21 | 22 | 23 | 0 0 0 0 0 0 24 | 25 | 2 2 0.01 26 | 27 | 10 28 | 29 | random 30 | 31 | 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /model_population/files/gazebo_population.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_population/files/gazebo_population.png -------------------------------------------------------------------------------- /model_population/files/model_list.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_population/files/model_list.png -------------------------------------------------------------------------------- /model_population/files/model_list_6-0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/model_population/files/model_list_6-0.png -------------------------------------------------------------------------------- /model_structure/files/box.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 0 0 0.5 0 0 0 5 | true 6 | 7 | 8 | 1.0 9 | 10 | 11 | 0.083 12 | 0.0 13 | 0.0 14 | 0.083 15 | 0.0 16 | 0.083 17 | 18 | 19 | 20 | 21 | 22 | 1 1 1 23 | 24 | 25 | 26 | 27 | 28 | 29 | 1 1 1 30 | 31 | 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /modifying_world/files/tutorialPhysicsTab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/modifying_world/files/tutorialPhysicsTab.png -------------------------------------------------------------------------------- /modifying_world/files/tutorialSceneTab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/modifying_world/files/tutorialSceneTab.png -------------------------------------------------------------------------------- /modifying_world/files/tutorialSceneTabExpanded.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/modifying_world/files/tutorialSceneTabExpanded.png -------------------------------------------------------------------------------- /nested_model/files/nested_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/nested_model/files/nested_model.png -------------------------------------------------------------------------------- /nested_model/files/nested_model_joint.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/nested_model/files/nested_model_joint.png -------------------------------------------------------------------------------- /occupiedevent/tutorial.md: -------------------------------------------------------------------------------- 1 | # Overview 2 | 3 | The [SimEventsPlugin](http://gazebosim.org/api/code/dev/classgazebo_1_1SimEventsPlugin.html) contains multiple components, one of which is the 4 | [OccupiedEvent](http://gazebosim.org/api/code/dev/classgazebo_1_1OccupiedEventSource.html). The OccupiedEvent will send a message on a topic whenever a model 5 | occupies a specified three dimensional region. 6 | 7 | # Usage and Example 8 | 9 | The OccupiedEvent component is instantiated through the 10 | `libSimEventsPlugin.so` and relies on at least one `` and ``, 11 | where the `` has a `` of `occupied`. 12 | 13 | In the following example, a region is specified as a box volume with 14 | a minimum corner at `0, 0, 0` and a maximum corner at `1, 1, 1` in the world 15 | coordinate frame. The name of this region is `region1`. An ``, of 16 | `` occupied, with the name `region1_event` is also specified that uses 17 | `region1`. When a model occupies `region1` a [string 18 | message](http://gazebosim.org/api/msgs/dev/gz__string_8proto.html) with 19 | a data value of "0" is sent on the `~/elevator` topic. 20 | 21 | ~~~ 22 | 23 | 24 | 25 | region1 26 | 27 | 0 0 0 28 | 0 1 1 29 | 30 | 31 | 32 | 33 | region1_event 34 | occupied 35 | region1 36 | ~/elevator 37 | 0 38 | 39 | 40 | 41 | ~~~ 42 | 43 | Multiple regions and events may be specified. See the 44 | [worlds/elevator.world](https://github.com/osrf/gazebo/blob/master/worlds/elevator.world) for a longer example. 45 | -------------------------------------------------------------------------------- /oculus/files/display_setup.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/oculus/files/display_setup.png -------------------------------------------------------------------------------- /oculus/files/display_setup2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/oculus/files/display_setup2.png -------------------------------------------------------------------------------- /parallel/files/dual_pr2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/parallel/files/dual_pr2.jpg -------------------------------------------------------------------------------- /parallel/files/pendulums.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/parallel/files/pendulums.jpg -------------------------------------------------------------------------------- /parallel/files/pr2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/parallel/files/pr2.jpg -------------------------------------------------------------------------------- /parallel/files/revolute_joint_test_spit_unthrottled.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/parallel/files/revolute_joint_test_spit_unthrottled.png -------------------------------------------------------------------------------- /parallel/files/revolute_joint_test_unthrottled.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/parallel/files/revolute_joint_test_unthrottled.png -------------------------------------------------------------------------------- /parallel/files/run_dual_pr2_test.bash: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | mkdir dual_pr2 || true 4 | wget https://raw.githubusercontent.com/osrf/gazebo/diagnostics_scpeters/worlds/dual_pr2.world 5 | 6 | for i in 0 1 2 3 4 7 | do 8 | gzserver --verbose -o unthrottled$i dual_pr2.world \ 9 | & sleep 2 && gz topic -e /gazebo/default/diagnostics | grep real_time_factor | awk -F: '{print $2}' > dual_pr2/unthrottled$i.csv \ 10 | & sleep 30 ; killall -9 gazebo gzclient gzserver gz 11 | done 12 | 13 | for i in 0 1 2 3 4 14 | do 15 | gzserver --verbose -o split_unthrottled$i dual_pr2.world \ 16 | & sleep 2 && gz topic -e /gazebo/default/diagnostics | grep real_time_factor | awk -F: '{print $2}' > dual_pr2/split_unthrottled$i.csv \ 17 | & sleep 30 ; killall -9 gazebo gzclient gzserver gz 18 | done 19 | -------------------------------------------------------------------------------- /parallel/files/run_pendulums_test.bash: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | mkdir revolute_joint_test || true 4 | wget https://raw.githubusercontent.com/osrf/gazebo/diagnostics_scpeters/test/worlds/revolute_joint_test.world 5 | for i in 0 1 2 3 4 5 6 6 | do 7 | gzserver --verbose -o unthrottled$i revolute_joint_test.world \ 8 | & sleep 2 && gz topic -e /gazebo/default/diagnostics | grep real_time_factor | awk -F: '{print $2}' > revolute_joint_test/unthrottled$i.csv \ 9 | & sleep 30 ; killall -9 gazebo gzclient gzserver gz 10 | done 11 | 12 | for i in 0 1 2 3 4 5 6 13 | do 14 | gzserver --verbose -o split_unthrottled$i revolute_joint_test.world \ 15 | & sleep 2 && gz topic -e /gazebo/default/diagnostics | grep real_time_factor | awk -F: '{print $2}' > revolute_joint_test/split_unthrottled$i.csv \ 16 | & sleep 30 ; killall -9 gazebo gzclient gzserver gz 17 | done 18 | -------------------------------------------------------------------------------- /parallel/files/run_pr2_test.bash: -------------------------------------------------------------------------------- 1 | #! /bin/bash 2 | 3 | mkdir pr2 || true 4 | wget https://raw.githubusercontent.com/osrf/gazebo/diagnostics_scpeters/worlds/pr2.world 5 | for i in 0 1 2 3 4 6 | do 7 | gzserver --verbose -o unthrottled$i pr2.world \ 8 | & sleep 2 && gz topic -e /gazebo/default/diagnostics | grep real_time_factor | awk -F: '{print $2}' > pr2/unthrottled$i.csv \ 9 | & sleep 30 ; killall -9 gazebo gzclient gzserver gz 10 | done 11 | 12 | for i in 0 1 2 3 4 13 | do 14 | gzserver --verbose -o split_unthrottled$i pr2.world \ 15 | & sleep 2 && gz topic -e /gazebo/default/diagnostics | grep real_time_factor | awk -F: '{print $2}' > pr2/split_unthrottled$i.csv \ 16 | & sleep 30 ; killall -9 gazebo gzclient gzserver gz 17 | done 18 | -------------------------------------------------------------------------------- /parallel/files/show_parallel_results.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python3 2 | 3 | import sys 4 | 5 | import matplotlib # noqa: F401 6 | import matplotlib.pyplot as plt 7 | 8 | import numpy as np # noqa: F401 9 | 10 | import pandas as pd 11 | 12 | 13 | def plot_result(name_physics): 14 | dataframe_data = pd.DataFrame() 15 | names = [] 16 | for i in range(7): 17 | name = name_physics + str(i) + '.csv' 18 | try: 19 | dataframe = pd.read_csv(sys.argv[1] + name, skiprows=0, sep=',', engine='python') 20 | dataframe.columns = [name] 21 | dataframe_data[name] = dataframe[name] 22 | names.append(name) 23 | except Exception as e: 24 | pass 25 | ax = dataframe_data[names].plot() 26 | ax.set_ylabel('Realtime factor') 27 | ax.set_title(name_physics) 28 | 29 | 30 | plot_result('unthrottled') 31 | plot_result('split_unthrottled') 32 | plt.show() 33 | -------------------------------------------------------------------------------- /physics_params/files/cone_pyramid.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/physics_params/files/cone_pyramid.png -------------------------------------------------------------------------------- /player_camera/tutorial.md: -------------------------------------------------------------------------------- 1 | # Introduction 2 | 3 | [Player](http://playerstage.sourceforge.net) is a robot control framework, 4 | please visit their [website](http://playerstage.sourceforge.net) for more 5 | information. 6 | 7 | This tutorial covers connecting the camera Player interfaces to Gazebo. 8 | 9 | Create a working directory 10 | 11 | ~~~ 12 | cd; mkdir gazebo_camera; cd gazebo_camera 13 | ~~~ 14 | 15 | # Player Config 16 | 17 | Copy the config script below into a file called `camera.cfg`. The following script is also accessible via this [link](https://github.com/osrf/gazebo/raw/master/examples/player/camera/camera.cfg). 18 | 19 | 21 | 22 | # Run 23 | 24 | Run Gazebo 25 | 26 | ~~~ 27 | gazebo worlds/pioneer2dx_camera.world 28 | ~~~ 29 | 30 | Run Player 31 | 32 | ~~~ 33 | player camera.cfg 34 | ~~~ 35 | 36 | Run playerv 37 | 38 | ~~~ 39 | playerv 40 | ~~~ 41 | 42 | You can now visualize the camera inside playerv. 43 | -------------------------------------------------------------------------------- /player_laser/tutorial.md: -------------------------------------------------------------------------------- 1 | # Introduction 2 | 3 | [Player](http://playerstage.sourceforge.net) is a robot control framework, 4 | please visit their [website](http://playerstage.sourceforge.net) for more 5 | information. 6 | 7 | This tutorial covers connecting the laser Player interfaces to Gazebo. 8 | 9 | Create a working directory 10 | 11 | ~~~ 12 | cd; mkdir gazebo_laser; cd gazebo_laser 13 | ~~~ 14 | 15 | # Player Config 16 | 17 | Copy the config script below into a file called `laser.cfg`. The following script is also accessible via this [link](https://github.com/osrf/gazebo/raw/master/examples/player/laser/laser.cfg). 18 | 19 | 21 | 22 | # Run 23 | 24 | Run Gazebo 25 | 26 | ~~~ 27 | gazebo worlds/pioneer2dx_laser.world 28 | ~~~ 29 | 30 | Run Player 31 | 32 | ~~~ 33 | player laser.cfg 34 | ~~~ 35 | 36 | Run playerv 37 | 38 | ~~~ 39 | playerv 40 | ~~~ 41 | 42 | You can now visualize the laser inside playerv. 43 | -------------------------------------------------------------------------------- /player_position/tutorial.md: -------------------------------------------------------------------------------- 1 | # Introduction 2 | 3 | [Player](http://playerstage.sourceforge.net) is a robot control framework, 4 | please visit their [website](http://playerstage.sourceforge.net) for more 5 | information. 6 | 7 | This tutorial covers connecting the position2d Player interfaces to Gazebo. 8 | 9 | Create a working directory 10 | 11 | ~~~ 12 | cd; mkdir gazebo_position2d; cd gazebo_position2d 13 | ~~~ 14 | 15 | # Player Config 16 | 17 | Copy the config script below into a file called `position2d.cfg`. The following script is also accessible via this [link](https://github.com/osrf/gazebo/raw/master/examples/player/position2d/position2d.cfg). 18 | 19 | 21 | 22 | # Run 23 | 24 | Run Gazebo 25 | 26 | ~~~ 27 | gazebo worlds/pioneer2dx.world 28 | ~~~ 29 | 30 | Run Player 31 | 32 | ~~~ 33 | player position2d.cfg 34 | ~~~ 35 | 36 | Run playerv 37 | 38 | ~~~ 39 | playerv 40 | ~~~ 41 | 42 | You can now drive the pioneer2dx using playerv. 43 | -------------------------------------------------------------------------------- /plugins_model/tutorial.md: -------------------------------------------------------------------------------- 1 | #Prerequisites 2 | 3 | [Overview / HelloWorld](/tutorials?tut=plugins_hello_world) Plugin Tutorial 4 | 5 | **Note:** If you're continuing from the previous tutorial, make sure you put in the proper `#include` lines for this tutorial that are listed below. 6 | 7 | #Code 8 | 9 | Source: [ gazebo/examples/plugins/model_push](https://github.com/osrf/gazebo/blob/gazebo8/examples/plugins/model_push) 10 | 11 | Plugins allow complete access to the physical properties of models and their underlying elements (links, joints, collision objects). The following plugin will apply a linear velocity to its parent model. 12 | 13 | ~~~ 14 | $ cd ~/gazebo_plugin_tutorial 15 | $ gedit model_push.cc 16 | ~~~ 17 | 18 | Plugin Code: 19 | 20 | 21 | ## Compiling the Plugin 22 | 23 | Assuming the reader has gone through the [Hello WorldPlugin tutorial](/tutorials?tut=plugins_hello_world) all that needs to be done is to add the following lines to `~/gazebo_plugin_tutorial/CMakeLists.txt` 24 | 25 | 26 | 27 | Compiling this code will result in a shared library, `~/gazebo_plugin_tutorial/build/libmodel_push.so`, that can be inserted in a Gazebo simulation. 28 | 29 | ~~~ 30 | $ cd ~/gazebo_plugin_tutorial/build 31 | $ cmake ../ 32 | $ make 33 | ~~~ 34 | 35 | ## Running the Plugin 36 | 37 | This plugin is used in the world file `examples/plugins/model_push/model_push.world`. 38 | 39 | ~~~ 40 | $ cd ~/gazebo_plugin_tutorial 41 | $ gedit model_push.world 42 | ~~~ 43 | 44 | 45 | 46 | The hook to attach a plugin to a model is specified at the end of the model element block using: 47 | 48 | %%% 49 | 50 | %%% 51 | 52 | Add your library path to the `GAZEBO_PLUGIN_PATH`: 53 | 54 | ~~~ 55 | $ export GAZEBO_PLUGIN_PATH=$HOME/gazebo_plugin_tutorial/build:$GAZEBO_PLUGIN_PATH 56 | ~~~ 57 | 58 | To start simulation, run 59 | 60 | ~~~ 61 | $ cd ~/gazebo_plugin_tutorial/ 62 | $ gzserver -u model_push.world 63 | ~~~ 64 | 65 | The `-u` option starts the server in a paused state. 66 | 67 | In a separate terminal, start the gui 68 | 69 | ~~~ 70 | $ gzclient 71 | ~~~ 72 | 73 | Click on the play button in the gui to unpause the simulation, and you should see the box move. 74 | -------------------------------------------------------------------------------- /plugins_model/tutorial_1-9.md: -------------------------------------------------------------------------------- 1 | #Prerequisites 2 | 3 | [Overview / HelloWorld](/tutorials?tut=plugins_hello_world) Plugin Tutorial 4 | 5 | **Note:** If you're continuing from the previous tutorial, make sure you put in the proper `#include` lines for this tutorial that are listed below. 6 | 7 | #Code 8 | 9 | Source: [ gazebo/examples/plugins/model_push](https://github.com/osrf/gazebo/blob/gazebo_2.2/examples/plugins/model_push) 10 | 11 | Plugins allow complete access to the physical properties of models and their underlying elements (links, joints, collision objects). The following plugin will apply a linear velocity to its parent model. 12 | 13 | ~~~ 14 | $ cd ~/gazebo_plugin_tutorial 15 | $ gedit model_push.cc 16 | ~~~ 17 | 18 | Plugin Code: 19 | 20 | 21 | ## Compiling the Plugin 22 | 23 | Assuming the reader has gone through the [Hello WorldPlugin tutorial](/tutorials?tut=plugins_hello_world) all that needs to be done is to add the following lines to `~/gazebo_plugin_tutorial/CMakeLists.txt` 24 | 25 | 26 | 27 | Compiling this code will result in a shared library, `~/gazebo_plugin_tutorial/build/libmodel_push.so`, that can be inserted in a Gazebo simulation. 28 | 29 | ~~~ 30 | $ cd ~/gazebo_plugin_tutorial/build 31 | $ cmake ../ 32 | $ make 33 | ~~~ 34 | 35 | ## Running the Plugin 36 | 37 | This plugin is used in the world file `examples/plugins/model_push/model_push.world`. 38 | 39 | ~~~ 40 | $ cd ~/gazebo_plugin_tutorial 41 | $ gedit model_push.world 42 | ~~~ 43 | 44 | 45 | 46 | The hook to attach a plugin to a model is specified at the end of the model element block using: 47 | 48 | %%% 49 | 50 | %%% 51 | 52 | Add your library path to the `GAZEBO_PLUGIN_PATH`: 53 | 54 | ~~~ 55 | $ export GAZEBO_PLUGIN_PATH=$HOME/gazebo_plugin_tutorial/build:$GAZEBO_PLUGIN_PATH 56 | ~~~ 57 | 58 | To start simulation, run 59 | 60 | ~~~ 61 | $ cd ~/gazebo_plugin_tutorial/ 62 | $ gzserver -u model_push.world 63 | ~~~ 64 | 65 | The `-u` option starts the server in a paused state. 66 | 67 | In a separate terminal, start the gui 68 | 69 | ~~~ 70 | $ gzclient 71 | ~~~ 72 | 73 | Click on the play button in the gui to unpause the simulation, and you should see the box move. 74 | -------------------------------------------------------------------------------- /preset_manager/files/preset_plot_annotated.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/preset_manager/files/preset_plot_annotated.png -------------------------------------------------------------------------------- /preset_manager/files/switch_profiles.sh: -------------------------------------------------------------------------------- 1 | #!/bin/sh 2 | 3 | set -x 4 | gazebo --verbose preset_example.world -o ode_200iters & 5 | 6 | echo start with 200 iterations 7 | sleep 5 8 | gz physics -o ode_70iters 9 | echo switch to 70 iterations 10 | echo simulation will go unstable 11 | sleep 5 12 | echo switch back to 200 iterations 13 | gz physics -o ode_200iters 14 | echo reset world 15 | gz world -r 16 | 17 | echo open plot window to show link pitch and yaw angles 18 | sleep 10 19 | echo 20 | for i in $(seq 5) 21 | do 22 | gz physics -o ode_500iters 23 | sleep 5 24 | gz physics -o ode_200iters 25 | sleep 5 26 | done 27 | set +x 28 | -------------------------------------------------------------------------------- /preset_manager/files/switch_profiles_sdf1_6.sh: -------------------------------------------------------------------------------- 1 | #!/bin/sh 2 | 3 | set -x 4 | gazebo --verbose preset_example_sdf1_6.world -o ode_200iters & 5 | 6 | echo start with 200 iterations 7 | sleep 5 8 | gz physics -o ode_70iters 9 | echo switch to 70 iterations 10 | echo simulation will go unstable 11 | sleep 5 12 | echo switch back to 200 iterations 13 | gz physics -o ode_200iters 14 | echo reset world 15 | gz world -r 16 | 17 | echo open plot window to show link pitch and yaw angles 18 | sleep 10 19 | echo 20 | for i in $(seq 5) 21 | do 22 | gz physics -o ode_500iters 23 | sleep 5 24 | gz physics -o ode_200iters 25 | sleep 5 26 | done 27 | set +x 28 | -------------------------------------------------------------------------------- /preset_manager/files/worldtab.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/preset_manager/files/worldtab.png -------------------------------------------------------------------------------- /profiler/files/Remotery_OdePhysics.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/profiler/files/Remotery_OdePhysics.png -------------------------------------------------------------------------------- /profiler/files/SensorManagerLoop.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/profiler/files/SensorManagerLoop.png -------------------------------------------------------------------------------- /profiler/files/gzserverLoop.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/profiler/files/gzserverLoop.png -------------------------------------------------------------------------------- /random_numbers/tutorial.md: -------------------------------------------------------------------------------- 1 | # Introduction 2 | 3 | Gazebo makes use of a random number generator. By default the seed is set to the PID of the process running Gazebo. It is possible to manually set the random number seed. The advantage of this feature is to obtain a deterministic sequence of random numbers, which is good for test repeatability. 4 | 5 | # Command line 6 | 7 | Gazebo can be initialized with a random number seed on the command line using the `--seed` argument: 8 | 9 | ~~~ 10 | gazebo --seed 11 | ~~~ 12 | 13 | # Message 14 | 15 | Gazebo listens to the `~/world_control` topic, which requires messages of type [msgs::WorldControl](http://osrf-distributions.s3.amazonaws.com/gazebo/msg-api/dev/world__control_8proto.html). The world control message may contain a random number seed. 16 | -------------------------------------------------------------------------------- /ros2_installing/figs/gazebo_ros_diff_drive.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros2_installing/figs/gazebo_ros_diff_drive.png -------------------------------------------------------------------------------- /ros2_installing/figs/gazebo_ros_diff_drive_lin_vel.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros2_installing/figs/gazebo_ros_diff_drive_lin_vel.gif -------------------------------------------------------------------------------- /ros_advanced/RosGUI.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_advanced/RosGUI.png -------------------------------------------------------------------------------- /ros_advanced/pioneer_flying.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_advanced/pioneer_flying.png -------------------------------------------------------------------------------- /ros_advanced/tutorial.md: -------------------------------------------------------------------------------- 1 | # Tutorial: ROS Advanced Integration 2 | 3 | ## Dynamic Reconfigure 4 | 5 | Some of the physics properties can be adjusted within Gazebo as we described in the [modifying a world tutorial](/tutorials?tut=modifying_world&cat=build_world). In addition, we can modify this properties using ROS's dynamic reconfigure mechanism. 6 | 7 | As an example, we'll invert the gravity in the simulation. Make sure you have the following installed for jade: 8 | 9 | ~~~ 10 | sudo apt-get install ros-jade-rqt-common-plugins ros-jade-dynamic-reconfigure 11 | ~~~ 12 | 13 | Or these packages for kinetic: 14 | 15 | ~~~ 16 | sudo apt-get install ros-kinetic-rqt-common-plugins ros-kinetic-dynamic-reconfigure 17 | ~~~ 18 | 19 | Start Gazebo: 20 | 21 | ~~~ 22 | rosrun gazebo_ros gazebo 23 | ~~~ 24 | 25 | Let's insert a model in gazebo before making any change in the physics. Go ahead and click ''Insert'' in the left side of the gazebo main window. Click on the ''Pioneer 2DX'' robot model. 26 | 27 | Start RosGui tool for interacting with gazebo in runtime: 28 | 29 | ~~~ 30 | rosrun rqt_gui rqt_gui 31 | ~~~ 32 | 33 | 34 | [[file:RosGUI.png|600px]] 35 | 36 | Resize the rqt (a.k.a. RosGui) tool until you see something similar to the upper picture. Click on ''gazebo'' in the left side of rqt. You will see the physics parameter list that you will be able to modify. Change the ''gravity_z'' parameter to ''+9.8'' and you should see how the gravity affects your robot. 37 | 38 | [[file:pioneer_flying.png|600px]] 39 | 40 | -------------------------------------------------------------------------------- /ros_comm/Coke_Can.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_comm/Coke_Can.png -------------------------------------------------------------------------------- /ros_comm/Coke_Can_Flying.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_comm/Coke_Can_Flying.png -------------------------------------------------------------------------------- /ros_comm/FloatingCokeCan.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_comm/FloatingCokeCan.png -------------------------------------------------------------------------------- /ros_comm/HoverCoke.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_comm/HoverCoke.png -------------------------------------------------------------------------------- /ros_comm/rotating_link.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_comm/rotating_link.png -------------------------------------------------------------------------------- /ros_control/Gazebo_ros_transmission.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_control/Gazebo_ros_transmission.png -------------------------------------------------------------------------------- /ros_control/rqt_controller_tuning.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_control/rqt_controller_tuning.png -------------------------------------------------------------------------------- /ros_control/rqt_dynamnic_reconfigure_pid.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_control/rqt_dynamnic_reconfigure_pid.png -------------------------------------------------------------------------------- /ros_depth_camera/depth_camera_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_depth_camera/depth_camera_rviz.png -------------------------------------------------------------------------------- /ros_depth_camera/depth_camera_scene.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_depth_camera/depth_camera_scene.png -------------------------------------------------------------------------------- /ros_depth_camera/files/kinect.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_depth_camera/files/kinect.zip -------------------------------------------------------------------------------- /ros_depth_camera/rviz_topics.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_depth_camera/rviz_topics.png -------------------------------------------------------------------------------- /ros_gzplugins/figs/camera.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_gzplugins/figs/camera.png -------------------------------------------------------------------------------- /ros_gzplugins/figs/cameraView.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_gzplugins/figs/cameraView.png -------------------------------------------------------------------------------- /ros_gzplugins/figs/gazebo_laser_scan.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_gzplugins/figs/gazebo_laser_scan.png -------------------------------------------------------------------------------- /ros_gzplugins/figs/rviz_laser_scan.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_gzplugins/figs/rviz_laser_scan.png -------------------------------------------------------------------------------- /ros_installing/figs/800px-EmptyGazebo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_installing/figs/800px-EmptyGazebo.png -------------------------------------------------------------------------------- /ros_overview/figs/775px-Gazebo_ros_api.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_overview/figs/775px-Gazebo_ros_api.png -------------------------------------------------------------------------------- /ros_roslaunch/figs/GasStation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_roslaunch/figs/GasStation.png -------------------------------------------------------------------------------- /ros_roslaunch/figs/Gas_baxter.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_roslaunch/figs/Gas_baxter.png -------------------------------------------------------------------------------- /ros_roslaunch/figs/PR2_GasStation.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_roslaunch/figs/PR2_GasStation.png -------------------------------------------------------------------------------- /ros_urdf/figs/Rrbot_rviz.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_urdf/figs/Rrbot_rviz.png -------------------------------------------------------------------------------- /ros_urdf/figs/Swinging_Arm.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/ros_urdf/figs/Swinging_Arm.png -------------------------------------------------------------------------------- /screenshot/files/screenshot_icon_gzclient.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/screenshot/files/screenshot_icon_gzclient.png -------------------------------------------------------------------------------- /screenshot/files/screenshot_icon_gzclient_6-0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/screenshot/files/screenshot_icon_gzclient_6-0.png -------------------------------------------------------------------------------- /screenshot/tutorial.md: -------------------------------------------------------------------------------- 1 | # Capture screenshots 2 | 3 | To capture a screenshot of the scene displayed in the Gazebo 3D render window, find and click on the camera icon on the toolbar above the render window. 4 | 5 | [[file:files/screenshot_icon_gzclient_6-0.png|640px]] 6 | 7 | # Screenshot save location 8 | 9 | The captured image will be saved to ~/.gazebo/pictures with a timestamped filename. 10 | -------------------------------------------------------------------------------- /screenshot/tutorial_1-9.md: -------------------------------------------------------------------------------- 1 | # Capture screenshots 2 | 3 | To capture a screenshot of the scene displayed in the Gazebo 3D render window, find and click on the camera icon on the toolbar above the render window. 4 | 5 | [[file:files/screenshot_icon_gzclient.png|640px]] 6 | 7 | # Screenshot save location 8 | 9 | The captured image will be saved to ~/.gazebo/pictures with a timestamped filename. 10 | -------------------------------------------------------------------------------- /sensor_noise/files/Noisy_camera_visualizer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/sensor_noise/files/Noisy_camera_visualizer.png -------------------------------------------------------------------------------- /sensor_noise/files/Noisy_laser_inserted.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/sensor_noise/files/Noisy_laser_inserted.png -------------------------------------------------------------------------------- /sensor_noise/files/Noisy_laser_visualizer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/sensor_noise/files/Noisy_laser_visualizer.png -------------------------------------------------------------------------------- /sensor_noise/files/Topic_visualizer.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/sensor_noise/files/Topic_visualizer.png -------------------------------------------------------------------------------- /set_velocity/examples/set_vel_plugin/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.6) 2 | project(SetVelPlugin) 3 | 4 | find_package(gazebo REQUIRED) 5 | 6 | include_directories(include ${GAZEBO_INCLUDE_DIRS}) 7 | link_directories(${GAZEBO_LIBRARY_DIRS}) 8 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}") 9 | 10 | add_library(SetLinkVelocityPlugin SHARED src/SetLinkVelocityPlugin.cpp) 11 | target_link_libraries(SetLinkVelocityPlugin ${GAZEBO_LIBRARIES}) 12 | 13 | add_library(SetJointVelocityPlugin SHARED src/SetJointVelocityPlugin.cpp) 14 | target_link_libraries(SetJointVelocityPlugin ${GAZEBO_LIBRARIES}) 15 | 16 | -------------------------------------------------------------------------------- /set_velocity/examples/set_vel_plugin/include/ode_perfect_angular.hh: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #ifndef GAZEBO_TUTORIALS_SET_VELOCITY_ODE_PERFECT_ANGULAR_HH_ 10 | #define GAZEBO_TUTORIALS_SET_VELOCITY_ODE_PERFECT_ANGULAR_HH_ 11 | 12 | using namespace gazebo; 13 | 14 | namespace gazebo 15 | { 16 | ////////////////////////////////////////////////// 17 | /// \brief uses joint motors to perfectly control velocity (ODE only) 18 | class OdePerfectAngularVelController 19 | { 20 | public: OdePerfectAngularVelController() 21 | { 22 | } 23 | 24 | public: ~OdePerfectAngularVelController() 25 | { 26 | this->Stop(); 27 | } 28 | 29 | /// \brief start controlling the angular velocity of an object 30 | /// \param[in] _link the link to move at the given velocity 31 | /// \param[in] _vel world velocity to move the link at 32 | /// \param[in] _maxTorque Maximum torque to apply each timestep 33 | public: void Start( 34 | physics::LinkPtr _link, math::Vector3 _vel, double _maxTorque) 35 | { 36 | this->Stop(); 37 | // create revolute joint with the world as a parent 38 | physics::ModelPtr model = _link->GetModel(); 39 | physics::WorldPtr world = physics::get_world("default"); 40 | physics::PhysicsEnginePtr engine = world->GetPhysicsEngine(); 41 | this->joint = engine->CreateJoint("revolute"); 42 | this->joint->SetName(model->GetName() + "__perfect_ang_joint__"); 43 | physics::LinkPtr worldLink = 44 | boost::dynamic_pointer_cast(world->GetByName("world")); 45 | math::Pose jointOrigin; 46 | this->joint->Load(worldLink, _link, jointOrigin); 47 | this->joint->Init(); 48 | double magnitude = _vel.GetLength(); 49 | this->joint->SetAxis(0, _vel.Normalize()); 50 | this->joint->SetParam("fmax", 0, _maxTorque); 51 | this->joint->SetParam("vel", 0, magnitude); 52 | } 53 | 54 | public: void Stop() 55 | { 56 | //remove the joint from the world 57 | if (this->joint) 58 | { 59 | this->joint->SetParam("fmax", 0, 0.0); 60 | this->joint->Detach(); 61 | this->joint->Fini(); 62 | this->joint.reset(); 63 | } 64 | } 65 | 66 | private: physics::JointPtr joint; 67 | }; 68 | } 69 | #endif 70 | -------------------------------------------------------------------------------- /set_velocity/examples/set_vel_plugin/include/ode_perfect_linear.hh: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | 9 | #ifndef GAZEBO_TUTORIALS_SET_VELOCITY_ODE_PERFECT_LINEAR_HH_ 10 | #define GAZEBO_TUTORIALS_SET_VELOCITY_ODE_PERFECT_LINEAR_HH_ 11 | 12 | namespace gazebo 13 | { 14 | ////////////////////////////////////////////////// 15 | /// \brief uses joint motors to perfectly control velocity (ODE only) 16 | class OdePerfectLinearVelController 17 | { 18 | public: OdePerfectLinearVelController() 19 | { 20 | } 21 | 22 | public: ~OdePerfectLinearVelController() 23 | { 24 | this->Stop(); 25 | } 26 | 27 | /// \brief start controlling the linear velocity of an object 28 | /// \param[in] _link the link to move at the given velocity 29 | /// \param[in] _vel world velocity to move the link at 30 | /// \param[in] _maxForce Maximum force to apply each timestep 31 | public: void Start( 32 | physics::LinkPtr _link, math::Vector3 _vel, double _maxForce) 33 | { 34 | this->Stop(); 35 | // create prismatic joint with the world as a parent 36 | physics::ModelPtr model = _link->GetModel(); 37 | physics::WorldPtr world = physics::get_world("default"); 38 | physics::PhysicsEnginePtr engine = world->GetPhysicsEngine(); 39 | this->joint = engine->CreateJoint("prismatic"); 40 | this->joint->SetName(model->GetName() + "__perfect_lin_joint__"); 41 | physics::LinkPtr worldLink = boost::dynamic_pointer_cast( 42 | world->GetByName("world")); 43 | math::Pose jointOrigin; 44 | this->joint->Load(worldLink, _link, jointOrigin); 45 | this->joint->Init(); 46 | double magnitude = _vel.GetLength(); 47 | this->joint->SetAxis(0, _vel.Normalize()); 48 | this->joint->SetParam("fmax", 0, _maxForce); 49 | this->joint->SetParam("vel", 0, magnitude); 50 | } 51 | 52 | public: void Stop() 53 | { 54 | //remove the joint from the world 55 | if (joint) 56 | { 57 | this->joint->SetParam("fmax", 0, 0.0); 58 | this->joint->Detach(); 59 | this->joint->Fini(); 60 | this->joint.reset(); 61 | } 62 | } 63 | 64 | private: physics::JointPtr joint; 65 | }; 66 | } 67 | #endif 68 | -------------------------------------------------------------------------------- /set_velocity/pictures/set_joint_velocity.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/set_velocity/pictures/set_joint_velocity.gif -------------------------------------------------------------------------------- /set_velocity/pictures/set_link_velocity.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/set_velocity/pictures/set_link_velocity.gif -------------------------------------------------------------------------------- /simple_gripper/files/Simple-gripper-1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/simple_gripper/files/Simple-gripper-1.png -------------------------------------------------------------------------------- /simple_gripper/files/Simple-gripper-joints.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/simple_gripper/files/Simple-gripper-joints.png -------------------------------------------------------------------------------- /simple_gripper/files/Simple-gripper-joints_5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/simple_gripper/files/Simple-gripper-joints_5.png -------------------------------------------------------------------------------- /simple_gripper/files/Simple_gripper_joint_control_1_4.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/simple_gripper/files/Simple_gripper_joint_control_1_4.png -------------------------------------------------------------------------------- /simple_gripper/files/Simple_gripper_joint_control_1_5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/simple_gripper/files/Simple_gripper_joint_control_1_5.png -------------------------------------------------------------------------------- /simple_gripper/files/gripper.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | model://ground_plane 8 | 9 | 10 | 11 | 12 | model://sun 13 | 14 | 15 | 16 | model://my_gripper 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /simple_gripper/files/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | My Gripper 5 | 1.0 6 | simple_gripper.sdf 7 | 8 | 9 | My Name 10 | me@my.email 11 | 12 | 13 | 14 | My awesome robot. 15 | 16 | 17 | -------------------------------------------------------------------------------- /static_map_plugin/files/static_map_models.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/static_map_plugin/files/static_map_models.png -------------------------------------------------------------------------------- /static_map_plugin/files/static_map_plugin.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/static_map_plugin/files/static_map_plugin.jpg -------------------------------------------------------------------------------- /system_plugin/tutorial.md: -------------------------------------------------------------------------------- 1 | #Prerequisites 2 | 3 | [Overview / HelloWorld](/tutorials?tut=plugins_hello_world) Plugin Tutorial 4 | 5 | # Overview 6 | 7 | Source: [gazebo/examples/plugins/system\_gui\_plugin](https://github.com/osrf/gazebo/blob/gazebo9/examples/plugins/system_gui_plugin) 8 | 9 | This tutorial will create a source file that is a system plugin for gzclient 10 | designed to save images into the directory `/tmp/gazebo_frames`. 11 | 12 | # Source code 13 | 14 | We'll start with the source file. Create a file called `system_gui.cc` with the following contents: 15 | 16 | ~~~ 17 | $ cd ~/gazebo_plugin_tutorial 18 | $ gedit system_gui.cc 19 | ~~~ 20 | 21 | Copy the following into `system_gui.cc` 22 | 23 | 24 | 25 | Both the `Load` and `Init` functions must not block. The `Load` and `Init` functions are called at startup, before Gazebo is loaded. 26 | 27 | On the first `Update`, we get a pointer to the user camera (the camera used in the graphical interface) and enable saving of frames. 28 | 29 | 1. Get the user camera 30 | 31 | this->userCam = gui::get_active_camera(); 32 | 33 | 2. Enable save frames 34 | 35 | this->userCam->EnableSaveFrame(true); 36 | 37 | 3. Set the location to save frames 38 | 39 | this->userCam->SetSaveFramePathname("/tmp/gazebo_frames"); 40 | 41 | ## Compiling Camera Plugin 42 | 43 | Assuming the reader has gone through the [Hello WorldPlugin tutorial](/tutorials?tut=plugins_hello_world) all that needs to be done is to add the following lines to `~/gazebo_plugin_tutorial/CMakeLists.txt` 44 | 45 | 46 | 47 | Rebuild, and you should end up with a libsystem_gui.so library. 48 | 49 | ~~~ 50 | $ cd ~/gazebo_plugin_tutorial/build 51 | $ cmake ../ 52 | $ make 53 | ~~~ 54 | 55 | ## Running Plugin 56 | 57 | First start gzserver in the background: 58 | 59 | ~~~ 60 | $ gzserver & 61 | ~~~ 62 | 63 | Run the client with plugin: 64 | 65 | ~~~ 66 | $ gzclient -g libsystem_gui.so 67 | ~~~ 68 | 69 | Inside `/tmp/gazebo_frames` you should see many saved images from the current plugin. 70 | 71 | 72 | Note: Remember to also terminate the background server process after you quit the client. In the same terminal, bring the process to foreground: 73 | 74 | ~~~ 75 | $ fg 76 | ~~~ 77 | 78 | and press `Ctrl-C` to abort the process. Alternatively, just kill the `gzserver` process: 79 | 80 | ~~~ 81 | $ killall gzserver 82 | ~~~ 83 | -------------------------------------------------------------------------------- /system_plugin/tutorial_5-0.md: -------------------------------------------------------------------------------- 1 | #Prerequisites 2 | 3 | [Overview / HelloWorld](/tutorials?tut=plugins_hello_world) Plugin Tutorial 4 | 5 | # Overview 6 | 7 | Source: [gazebo/examples/plugins/system\_gui\_plugin](https://github.com/osrf/gazebo/blob/gazebo5/examples/plugins/system_gui_plugin) 8 | 9 | This tutorial will create a source file that is a system plugin for gzclient 10 | designed to save images into the directory `/tmp/gazebo_frames`. 11 | 12 | # Source code 13 | 14 | We'll start with the source file. Create a file called `system_gui.cc` with the following contents: 15 | 16 | ~~~ 17 | $ cd ~/gazebo_plugin_tutorial 18 | $ gedit system_gui.cc 19 | ~~~ 20 | 21 | Copy the following into `system_gui.cc` 22 | 23 | 24 | 25 | Both the `Load` and `Init` functions must not block. The `Load` and `Init` functions are called at startup, before Gazebo is loaded. 26 | 27 | On the first `Update`, we get a pointer to the user camera (the camera used in the graphical interface) and enable saving of frames. 28 | 29 | 1. Get the user camera 30 | 31 | this->userCam = gui::get_active_camera(); 32 | 33 | 2. Enable save frames 34 | 35 | this->userCam->EnableSaveFrame(true); 36 | 37 | 3. Set the location to save frames 38 | 39 | this->userCam->SetSaveFramePathname("/tmp/gazebo_frames"); 40 | 41 | ## Compiling Camera Plugin 42 | 43 | Assuming the reader has gone through the [Hello WorldPlugin tutorial](/tutorials?tut=plugins_hello_world) all that needs to be done is to add the following lines to `~/gazebo_plugin_tutorial/CMakeLists.txt` 44 | 45 | 46 | 47 | Rebuild, and you should end up with a libsystem_gui.so library. 48 | 49 | ~~~ 50 | $ cd ~/gazebo_plugin_tutorial/build 51 | $ cmake ../ 52 | $ make 53 | ~~~ 54 | 55 | ## Running Plugin 56 | 57 | First start gzserver in the background: 58 | 59 | ~~~ 60 | $ gzserver & 61 | ~~~ 62 | 63 | Run the client with plugin: 64 | 65 | ~~~ 66 | $ gzclient -g libsystem_gui.so 67 | ~~~ 68 | 69 | Inside `/tmp/gazebo_frames` you should see many saved images from the current plugin. 70 | 71 | 72 | Note: Remember to also terminate the background server process after you quit the client. In the same terminal, bring the process to foreground: 73 | 74 | ~~~ 75 | $ fg 76 | ~~~ 77 | 78 | and press `Ctrl-C` to abort the process. Alternatively, just kill the `gzserver` process: 79 | 80 | ~~~ 81 | $ killall gzserver 82 | ~~~ 83 | -------------------------------------------------------------------------------- /torsional_friction/files/box_and_sphere.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/torsional_friction/files/box_and_sphere.png -------------------------------------------------------------------------------- /torsional_friction/files/radius_depth.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/torsional_friction/files/radius_depth.png -------------------------------------------------------------------------------- /visual_layers/files/layers_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/visual_layers/files/layers_1.png -------------------------------------------------------------------------------- /visual_layers/files/layers_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/visual_layers/files/layers_2.png -------------------------------------------------------------------------------- /visual_layers/tutorial.md: -------------------------------------------------------------------------------- 1 | # Overview 2 | 3 | With Gazebo 6 it is possible to add meta data to the visuals in your 4 | simulation. This tutorial explains how to add layer meta data to visuals so 5 | you can control which layers are visible via the graphical interface. 6 | 7 | # Assigning layers on SDF 8 | 9 | Currently, layers are identified by numbers. In your model SDF file, under 10 | each `` tag, you can add a `` tag for meta information and 11 | then a `` tag with the layer number as follows: 12 | 13 | 14 | 15 | 0 16 | 17 | ... 18 | 19 | 20 | Visuals without a layer assigned can't have their visibility toggled and 21 | will always be visible. 22 | 23 | # Visualizing layers 24 | 25 | An example [world](https://github.com/osrf/gazebo/blob/gazebo6/worlds/shapes_layers.world) is distributed with Gazebo. You can load this world using the following command: 26 | 27 | gazebo worlds/shapes_layers.world 28 | 29 | You can toggle the visibility of each layer via the `Layers` tab on the left panel: 30 | 31 | [[file:files/layers_1.png|640px]] 32 | 33 | [[file:files/layers_2.png|640px]] 34 | 35 | If no visuals on the simulation have a layer, the layers tab will be empty. 36 | -------------------------------------------------------------------------------- /wide_angle_camera/files/180.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/180.png -------------------------------------------------------------------------------- /wide_angle_camera/files/360.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/360.png -------------------------------------------------------------------------------- /wide_angle_camera/files/c_1.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/c_1.gif -------------------------------------------------------------------------------- /wide_angle_camera/files/c_2.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/c_2.gif -------------------------------------------------------------------------------- /wide_angle_camera/files/dfov.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/dfov.gif -------------------------------------------------------------------------------- /wide_angle_camera/files/dfov2.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/dfov2.gif -------------------------------------------------------------------------------- /wide_angle_camera/files/f.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/f.gif -------------------------------------------------------------------------------- /wide_angle_camera/files/fun.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/fun.gif -------------------------------------------------------------------------------- /wide_angle_camera/files/fun_inv.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/fun_inv.gif -------------------------------------------------------------------------------- /wide_angle_camera/files/r.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/osrf/gazebo_tutorials/5413e61d9dfb47a2ce5880b4e7ab184608728713/wide_angle_camera/files/r.gif --------------------------------------------------------------------------------