├── gazebo_ros
├── src
│ └── gazebo_ros
│ │ ├── __init__.py
│ │ └── gazebo_interface.py
├── .idea
│ └── gazebo_ros.iml
├── setup.py
├── colcon.pkg
├── scripts
│ ├── gdbrun
│ ├── libcommon.sh
│ ├── perf
│ ├── debug
│ ├── gzclient
│ ├── gzserver
│ ├── debug.bat
│ ├── gzclient.bat
│ ├── gzserver.bat
│ └── gazebo
├── test
│ ├── ros_network
│ │ ├── ros_network_disabled.test
│ │ ├── ros_network_default.test
│ │ └── no_gazebo_network_api.yaml
│ └── CMakeLists.txt
├── launch
│ ├── mud_world.launch
│ ├── rubble_world.launch
│ ├── shapes_world.launch
│ ├── willowgarage_world.launch
│ ├── range_world.launch
│ ├── elevator_world.launch
│ └── empty_world.launch
└── package.xml
├── gazebo_plugins
├── src
│ ├── gazebo_plugins
│ │ ├── __init__.py
│ │ └── gazebo_plugins_interface.py
│ ├── camera_synchronizer.cpp
│ ├── gazebo_ros_elevator.cpp
│ └── hokuyo_node.cpp
├── test
│ ├── tricycle_drive
│ │ ├── xacro
│ │ │ ├── .directory
│ │ │ ├── tricycle
│ │ │ │ ├── tricycle.xacro
│ │ │ │ ├── tricycle_chassis.xacro
│ │ │ │ ├── wheel.xacro
│ │ │ │ ├── wheel_actuated.xacro
│ │ │ │ ├── tricycle_body.xacro
│ │ │ │ ├── tricycle_plugins.xacro
│ │ │ │ └── inertia_tensors.xacro
│ │ │ └── materials.xacro
│ │ └── launch
│ │ │ ├── .directory
│ │ │ ├── tricycle_rviz.launch
│ │ │ ├── tricycle.urdf.launch
│ │ │ ├── tricycle.gazebo.launch
│ │ │ └── tricycle_drive_scenario.launch
│ ├── multi_robot_scenario
│ │ ├── meshes
│ │ │ └── p3dx
│ │ │ │ ├── top.stl
│ │ │ │ ├── swivel.stl
│ │ │ │ ├── back_rim.stl
│ │ │ │ ├── chassis.stl
│ │ │ │ ├── front_rim.stl
│ │ │ │ ├── back_sonar.stl
│ │ │ │ ├── front_sonar.stl
│ │ │ │ ├── left_hubcap.stl
│ │ │ │ ├── left_wheel.stl
│ │ │ │ ├── right_wheel.stl
│ │ │ │ ├── center_hubcap.stl
│ │ │ │ ├── center_wheel.stl
│ │ │ │ ├── right_hubcap.stl
│ │ │ │ └── Coordinates
│ │ ├── launch
│ │ │ ├── pioneer3dx.urdf.launch
│ │ │ ├── pioneer3dx.gazebo.launch
│ │ │ └── multi_robot_scenario.launch
│ │ └── xacro
│ │ │ ├── materials.xacro
│ │ │ ├── p3dx
│ │ │ ├── battery_block.xacro
│ │ │ ├── pioneer3dx_sonar.xacro
│ │ │ ├── pioneer3dx.xacro
│ │ │ ├── pioneer3dx_body.xacro
│ │ │ ├── pioneer3dx_plugins.xacro
│ │ │ ├── pioneer3dx_chassis.xacro
│ │ │ ├── pioneer3dx_wheel.xacro
│ │ │ └── inertia_tensors.xacro
│ │ │ ├── laser
│ │ │ ├── hokuyo.xacro
│ │ │ └── hokuyo_gpu.xacro
│ │ │ └── camera
│ │ │ └── camera.xacro
│ ├── bumper_test
│ │ └── test_bumper.launch
│ ├── camera
│ │ ├── distortion_barrel.cpp
│ │ ├── distortion_pincushion.cpp
│ │ ├── camera.cpp
│ │ ├── camera16bit.cpp
│ │ ├── multicamera.test
│ │ ├── distortion_barrel.test
│ │ ├── distortion_pincushion.test
│ │ ├── camera.test
│ │ ├── camera16bit.test
│ │ ├── depth_camera.test
│ │ ├── triggered_camera.test
│ │ └── camera.h
│ ├── p3d_test
│ │ ├── test_single_pendulum.launch
│ │ ├── test_double_pendulum.launch
│ │ ├── test_3_single_pendulums.launch
│ │ └── test_3_double_pendulums.launch
│ ├── spawn_test
│ │ ├── parameter_server_test.launch
│ │ └── spawn_robots.sh
│ ├── block_laser_clipping.test
│ ├── range
│ │ └── range_plugin.test
│ ├── set_model_state_test
│ │ └── set_model_state_test.test
│ ├── config
│ │ └── example_models.yaml
│ ├── test_worlds
│ │ └── gazebo_ros_block_laser_clipping.world
│ └── pub_joint_trajectory_test.cpp
├── test2
│ ├── meshes
│ │ ├── cube.wings
│ │ ├── cube_20k.stl
│ │ └── cube_30k.stl
│ ├── spawn_model
│ │ ├── spawn_box.launch
│ │ ├── spawn_box_file.launch
│ │ └── spawn_box_param.launch
│ ├── trimesh_tests
│ │ └── test_trimesh.launch
│ ├── contact_tolerance
│ │ └── contact_tolerance.launch
│ ├── lcp_tests
│ │ ├── balance.launch
│ │ ├── stack.launch
│ │ └── stacks.launch
│ ├── urdf
│ │ ├── box.urdf
│ │ └── cube.urdf
│ ├── large_models
│ │ ├── smaller_large_model.launch
│ │ ├── large_model.launch
│ │ └── large_models.world
│ └── CMakeLists_tests_pkg.txt
├── Media
│ └── models
│ │ └── chair
│ │ ├── textures.txt
│ │ ├── models
│ │ └── Chair.stl
│ │ ├── images
│ │ ├── texture0.jpg
│ │ └── texture1.jpg
│ │ └── doc.kml
├── colcon.pkg
├── setup.py
├── cfg
│ ├── GazeboRosCamera.cfg
│ ├── GazeboRosOpenniKinect.cfg
│ └── WheelSlip.cfg
├── scripts
│ ├── test_range.py
│ ├── test_block_laser_clipping.py
│ └── gazebo_model
├── include
│ └── gazebo_plugins
│ │ ├── gazebo_ros_template.h
│ │ ├── gazebo_ros_camera.h
│ │ ├── MultiCameraPlugin.h
│ │ ├── gazebo_ros_hand_of_god.h
│ │ ├── gazebo_ros_elevator.h
│ │ ├── gazebo_ros_multicamera.h
│ │ ├── gazebo_ros_triggered_multicamera.h
│ │ ├── gazebo_ros_triggered_camera.h
│ │ ├── gazebo_ros_harness.h
│ │ ├── gazebo_ros_bumper.h
│ │ ├── vision_reconfigure.h
│ │ ├── gazebo_ros_wheel_slip.h
│ │ └── gazebo_ros_video.h
└── package.xml
├── gazebo_msgs
├── srv
│ ├── JointRequest.srv
│ ├── BodyRequest.srv
│ ├── SetLinkState.srv
│ ├── SetModelState.srv
│ ├── DeleteLight.srv
│ ├── DeleteModel.srv
│ ├── SetJointTrajectory.srv
│ ├── SetJointProperties.srv
│ ├── GetWorldProperties.srv
│ ├── GetLightProperties.srv
│ ├── SetModelConfiguration.srv
│ ├── SetPhysicsProperties.srv
│ ├── GetLinkState.srv
│ ├── SetLightProperties.srv
│ ├── GetPhysicsProperties.srv
│ ├── GetJointProperties.srv
│ ├── GetModelProperties.srv
│ ├── SpawnModel.srv
│ ├── ApplyJointEffort.srv
│ ├── GetLinkProperties.srv
│ ├── SetLinkProperties.srv
│ ├── GetModelState.srv
│ └── ApplyBodyWrench.srv
├── msg
│ ├── SensorPerformanceMetric.msg
│ ├── PerformanceMetrics.msg
│ ├── ContactsState.msg
│ ├── LinkStates.msg
│ ├── ModelStates.msg
│ ├── ModelState.msg
│ ├── LinkState.msg
│ ├── ContactState.msg
│ ├── ODEJointProperties.msg
│ ├── ODEPhysics.msg
│ └── WorldState.msg
├── CMakeLists.txt
└── package.xml
├── gazebo_ros_pkgs
├── CMakeLists.txt
├── documentation
│ ├── gazebo_ros_api.odg
│ ├── gazebo_ros_api.pdf
│ ├── gazebo_ros_api.png
│ ├── gazebo_ros_transmission.odg
│ ├── gazebo_ros_transmission.pdf
│ └── gazebo_ros_transmission.png
└── package.xml
├── gazebo_dev
├── CMakeLists.txt
├── colcon.pkg
├── cmake
│ └── gazebo_dev-extras.cmake
└── package.xml
├── .gitignore
├── gazebo_ros_control
├── colcon.pkg
├── robot_hw_sim_plugins.xml
├── README.md
├── package.xml
└── CMakeLists.txt
├── README.md
└── CONTRIBUTING.md
/gazebo_ros/src/gazebo_ros/__init__.py:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/gazebo_plugins/src/gazebo_plugins/__init__.py:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/JointRequest.srv:
--------------------------------------------------------------------------------
1 | string joint_name # name of the joint requested
2 | ---
3 |
4 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/.directory:
--------------------------------------------------------------------------------
1 | [Dolphin]
2 | Timestamp=2013,10,18,16,23,17
3 | ViewMode=2
4 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/launch/.directory:
--------------------------------------------------------------------------------
1 | [Dolphin]
2 | Timestamp=2013,11,4,9,14,4
3 | Version=3
4 | ViewMode=2
5 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/SensorPerformanceMetric.msg:
--------------------------------------------------------------------------------
1 | string name
2 | float64 sim_update_rate
3 | float64 real_update_rate
4 | float64 fps
5 |
--------------------------------------------------------------------------------
/gazebo_ros/.idea/gazebo_ros.iml:
--------------------------------------------------------------------------------
1 |
2 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/PerformanceMetrics.msg:
--------------------------------------------------------------------------------
1 | Header header
2 |
3 | float64 real_time_factor
4 | gazebo_msgs/SensorPerformanceMetric[] sensors
5 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/meshes/cube.wings:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test2/meshes/cube.wings
--------------------------------------------------------------------------------
/gazebo_plugins/test2/meshes/cube_20k.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test2/meshes/cube_20k.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test2/meshes/cube_30k.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test2/meshes/cube_30k.stl
--------------------------------------------------------------------------------
/gazebo_msgs/srv/BodyRequest.srv:
--------------------------------------------------------------------------------
1 | string body_name # name of the body requested. body names are prefixed by model name, e.g. pr2::base_link
2 | ---
3 |
--------------------------------------------------------------------------------
/gazebo_plugins/Media/models/chair/textures.txt:
--------------------------------------------------------------------------------
1 | <../images/texture0.jpg> <../images/texture0.jpg>
2 | <../images/texture1.jpg> <../images/texture1.jpg>
3 |
--------------------------------------------------------------------------------
/gazebo_ros_pkgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.0.2)
2 | project(gazebo_ros_pkgs)
3 | find_package(catkin REQUIRED)
4 | catkin_metapackage()
5 |
--------------------------------------------------------------------------------
/gazebo_ros_pkgs/documentation/gazebo_ros_api.odg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_ros_pkgs/documentation/gazebo_ros_api.odg
--------------------------------------------------------------------------------
/gazebo_ros_pkgs/documentation/gazebo_ros_api.pdf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_ros_pkgs/documentation/gazebo_ros_api.pdf
--------------------------------------------------------------------------------
/gazebo_ros_pkgs/documentation/gazebo_ros_api.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_ros_pkgs/documentation/gazebo_ros_api.png
--------------------------------------------------------------------------------
/gazebo_plugins/Media/models/chair/models/Chair.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/Media/models/chair/models/Chair.stl
--------------------------------------------------------------------------------
/gazebo_plugins/Media/models/chair/images/texture0.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/Media/models/chair/images/texture0.jpg
--------------------------------------------------------------------------------
/gazebo_plugins/Media/models/chair/images/texture1.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/Media/models/chair/images/texture1.jpg
--------------------------------------------------------------------------------
/gazebo_msgs/msg/ContactsState.msg:
--------------------------------------------------------------------------------
1 | Header header # stamp
2 | gazebo_msgs/ContactState[] states # array of geom pairs in contact
3 |
--------------------------------------------------------------------------------
/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.odg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.odg
--------------------------------------------------------------------------------
/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.pdf:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.pdf
--------------------------------------------------------------------------------
/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_ros_pkgs/documentation/gazebo_ros_transmission.png
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/top.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/top.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/swivel.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/swivel.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_rim.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_rim.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/chassis.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/chassis.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_rim.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_rim.stl
--------------------------------------------------------------------------------
/gazebo_dev/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.0.2)
2 | project(gazebo_dev)
3 |
4 | find_package(catkin REQUIRED)
5 |
6 | catkin_package(
7 | CFG_EXTRAS gazebo_dev-extras.cmake
8 | )
9 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_sonar.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/back_sonar.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_sonar.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/front_sonar.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_hubcap.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_hubcap.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_wheel.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/left_wheel.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_wheel.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_wheel.stl
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SetLinkState.srv:
--------------------------------------------------------------------------------
1 | gazebo_msgs/LinkState link_state
2 | ---
3 | bool success # return true if set wrench successful
4 | string status_message # comments if available
5 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_hubcap.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_hubcap.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_wheel.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/center_wheel.stl
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_hubcap.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/ros-simulation/gazebo_ros_pkgs/HEAD/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/right_hubcap.stl
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SetModelState.srv:
--------------------------------------------------------------------------------
1 | gazebo_msgs/ModelState model_state
2 | ---
3 | bool success # return true if setting state successful
4 | string status_message # comments if available
5 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | # vi stuff
2 | .*.sw?
3 |
4 | # Python stuff
5 | *.pyc
6 |
7 | # Data files
8 | *.dat
9 | *.csv
10 |
11 | # Emacs temp files
12 | .#*
13 |
14 | # OSX Files
15 | .DS_Store
16 |
17 | CATKIN_IGNORE
18 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/launch/tricycle_rviz.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/LinkStates.msg:
--------------------------------------------------------------------------------
1 | # broadcast all link states in world frame
2 | string[] name # link names
3 | geometry_msgs/Pose[] pose # desired pose in world frame
4 | geometry_msgs/Twist[] twist # desired twist in world frame
5 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/DeleteLight.srv:
--------------------------------------------------------------------------------
1 | string light_name # name of the light to be deleted
2 | ---
3 | bool success # return true if deletion is successful
4 | string status_message # comments if available
5 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/ModelStates.msg:
--------------------------------------------------------------------------------
1 | # broadcast all model states in world frame
2 | string[] name # model names
3 | geometry_msgs/Pose[] pose # desired pose in world frame
4 | geometry_msgs/Twist[] twist # desired twist in world frame
5 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/DeleteModel.srv:
--------------------------------------------------------------------------------
1 | string model_name # name of the Gazebo Model to be deleted
2 | ---
3 | bool success # return true if deletion is successful
4 | string status_message # comments if available
5 |
--------------------------------------------------------------------------------
/gazebo_ros/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | from distutils.core import setup
3 | from catkin_pkg.python_setup import generate_distutils_setup
4 |
5 | d = generate_distutils_setup()
6 | d['packages'] = ['gazebo_ros']
7 | d['package_dir'] = {'':'src'}
8 |
9 | setup(**d)
10 |
--------------------------------------------------------------------------------
/gazebo_dev/colcon.pkg:
--------------------------------------------------------------------------------
1 | # Configuration file for colcon (https://colcon.readthedocs.io).
2 | #
3 | # Please see the doc for the details of the spec:
4 | # - https://colcon.readthedocs.io/en/released/user/configuration.html#colcon-pkg-files
5 |
6 | {
7 | "dependencies": ["Gazebo"],
8 | }
9 |
--------------------------------------------------------------------------------
/gazebo_plugins/colcon.pkg:
--------------------------------------------------------------------------------
1 | # Configuration file for colcon (https://colcon.readthedocs.io).
2 | #
3 | # Please see the doc for the details of the spec:
4 | # - https://colcon.readthedocs.io/en/released/user/configuration.html#colcon-pkg-files
5 |
6 | {
7 | "dependencies": ["Gazebo"],
8 | }
9 |
--------------------------------------------------------------------------------
/gazebo_plugins/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | from distutils.core import setup
3 | from catkin_pkg.python_setup import generate_distutils_setup
4 |
5 | d = generate_distutils_setup()
6 | d['packages'] = ['gazebo_plugins']
7 | d['package_dir'] = {'':'src'}
8 |
9 | setup(**d)
10 |
--------------------------------------------------------------------------------
/gazebo_ros/colcon.pkg:
--------------------------------------------------------------------------------
1 | # Configuration file for colcon (https://colcon.readthedocs.io).
2 | #
3 | # Please see the doc for the details of the spec:
4 | # - https://colcon.readthedocs.io/en/released/user/configuration.html#colcon-pkg-files
5 |
6 | {
7 | "dependencies": ["Gazebo"],
8 | }
9 |
--------------------------------------------------------------------------------
/gazebo_ros_control/colcon.pkg:
--------------------------------------------------------------------------------
1 | # Configuration file for colcon (https://colcon.readthedocs.io).
2 | #
3 | # Please see the doc for the details of the spec:
4 | # - https://colcon.readthedocs.io/en/released/user/configuration.html#colcon-pkg-files
5 |
6 | {
7 | "dependencies": ["Gazebo"],
8 | }
9 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SetJointTrajectory.srv:
--------------------------------------------------------------------------------
1 | string model_name
2 | trajectory_msgs/JointTrajectory joint_trajectory
3 | geometry_msgs/Pose model_pose
4 | bool set_model_pose
5 | bool disable_physics_updates # defaults to false
6 | ---
7 | bool success # return true if set wrench successful
8 | string status_message # comments if available
9 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/bumper_test/test_bumper.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SetJointProperties.srv:
--------------------------------------------------------------------------------
1 | string joint_name # name of joint
2 | gazebo_msgs/ODEJointProperties ode_joint_config # access to ODE joint dynamics properties
3 | ---
4 | bool success # return true if get successful
5 | string status_message # comments if available
6 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/GetWorldProperties.srv:
--------------------------------------------------------------------------------
1 | ---
2 | float64 sim_time # current sim time
3 | string[] model_names # list of models in the world
4 | bool rendering_enabled # if X is used
5 | bool success # return true if get successful
6 | string status_message # comments if available
7 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/distortion_barrel.cpp:
--------------------------------------------------------------------------------
1 | #include "distortion.h"
2 |
3 | TEST_F(DistortionTest, barrelDistortion)
4 | {
5 | cameraDistortionTest();
6 | }
7 |
8 | int main(int argc, char** argv)
9 | {
10 | ros::init(argc, argv, "gazebo_camera_barrel_distortion_test");
11 | testing::InitGoogleTest(&argc, argv);
12 | return RUN_ALL_TESTS();
13 | }
14 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/distortion_pincushion.cpp:
--------------------------------------------------------------------------------
1 | #include "distortion.h"
2 |
3 | TEST_F(DistortionTest, pincushionDistortion)
4 | {
5 | cameraDistortionTest();
6 | }
7 |
8 | int main(int argc, char** argv)
9 | {
10 | ros::init(argc, argv, "gazebo_camera_pincushion_distortion_test");
11 | testing::InitGoogleTest(&argc, argv);
12 | return RUN_ALL_TESTS();
13 | }
14 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/p3d_test/test_single_pendulum.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/GetLightProperties.srv:
--------------------------------------------------------------------------------
1 | string light_name # name of Gazebo Light
2 | ---
3 | std_msgs/ColorRGBA diffuse # diffuse color as red, green, blue, alpha
4 | float64 attenuation_constant
5 | float64 attenuation_linear
6 | float64 attenuation_quadratic
7 | bool success # return true if get successful
8 | string status_message # comments if available
9 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/spawn_test/parameter_server_test.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/camera.cpp:
--------------------------------------------------------------------------------
1 | #include "camera.h"
2 |
3 | // Test if the camera image is published at all, and that the timestamp
4 | // is not too long in the past.
5 | TEST_F(CameraTest, cameraSubscribeTest)
6 | {
7 | subscribeTest();
8 | }
9 |
10 | int main(int argc, char** argv)
11 | {
12 | ros::init(argc, argv, "gazebo_camera_test");
13 | testing::InitGoogleTest(&argc, argv);
14 | return RUN_ALL_TESTS();
15 | }
16 |
--------------------------------------------------------------------------------
/gazebo_ros_control/robot_hw_sim_plugins.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
7 |
8 | A default robot simulation interface which constructs joint handles from an SDF/URDF.
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/camera16bit.cpp:
--------------------------------------------------------------------------------
1 | #include "camera.h"
2 |
3 | // Test if the camera image is published at all, and that the timestamp
4 | // is not too long in the past.
5 | TEST_F(CameraTest, camera16bitSubscribeTest)
6 | {
7 | subscribeTest();
8 | }
9 |
10 | int main(int argc, char** argv)
11 | {
12 | ros::init(argc, argv, "gazebo_camera_test");
13 | testing::InitGoogleTest(&argc, argv);
14 | return RUN_ALL_TESTS();
15 | }
16 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/ModelState.msg:
--------------------------------------------------------------------------------
1 | # Set Gazebo Model pose and twist
2 | string model_name # model to set state (pose and twist)
3 | geometry_msgs/Pose pose # desired pose in reference frame
4 | geometry_msgs/Twist twist # desired twist in reference frame
5 | string reference_frame # set pose/twist relative to the frame of this entity (Body/Model)
6 | # leave empty or "world" or "map" defaults to world-frame
7 |
8 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/spawn_model/spawn_box.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/trimesh_tests/test_trimesh.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/gdbrun:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | extra_text=""
3 | if [ "$1" = "--break-main" ]; then
4 | extra_text="break main"
5 | shift
6 | fi
7 |
8 | EXEC="$1"
9 |
10 | shift
11 |
12 | run_text="run"
13 | for a in "$@"; do
14 | run_text="${run_text} \"$a\""
15 | done
16 |
17 | TMPFILE=/tmp/gdbrun.$$.$#.tmp
18 | cat > ${TMPFILE} <
2 |
3 |
4 |
5 |
8 |
9 |
11 |
12 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/contact_tolerance/contact_tolerance.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SetModelConfiguration.srv:
--------------------------------------------------------------------------------
1 | # Set joint positions for a model
2 | string model_name # model to set state
3 | string urdf_param_name # UNUSED
4 |
5 | string[] joint_names # list of joints to set positions. if joint is not listed here, preserve current position.
6 | float64[] joint_positions # set to this position.
7 | ---
8 | bool success # return true if setting state successful
9 | string status_message # comments if available
10 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/distortion_barrel.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
9 |
10 |
12 |
13 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/distortion_pincushion.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
9 |
10 |
12 |
13 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/block_laser_clipping.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
8 |
9 |
11 |
12 |
--------------------------------------------------------------------------------
/gazebo_ros_control/README.md:
--------------------------------------------------------------------------------
1 | # Gazebo ros_control Interfaces
2 |
3 | This is a ROS package for integrating the `ros_control` controller architecture
4 | with the [Gazebo](http://gazebosim.org/) simulator.
5 |
6 | This package provides a Gazebo plugin which instantiates a ros_control
7 | controller manager and connects it to a Gazebo model.
8 |
9 | [Documentation](http://gazebosim.org/tutorials?tut=ros_control) is provided on Gazebo's website.
10 |
11 | ## Future Direction
12 |
13 | - Implement transmissions
14 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.urdf.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SetPhysicsProperties.srv:
--------------------------------------------------------------------------------
1 | # sets pose and twist of a link. All children link poses/twists of the URDF tree will be updated accordingly
2 | float64 time_step # dt in seconds
3 | float64 max_update_rate # throttle maximum physics update rate
4 | geometry_msgs/Vector3 gravity # gravity vector (e.g. earth ~[0,0,-9.81])
5 | gazebo_msgs/ODEPhysics ode_config # configurations for ODE
6 | ---
7 | bool success # return true if set wrench successful
8 | string status_message # comments if available
9 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/meshes/p3dx/Coordinates:
--------------------------------------------------------------------------------
1 | =========================================
2 | Location Coordinates (x,y,z)
3 | =========================================
4 |
5 | Chassis : -0.045 0 0.148
6 | Top : -0.045 0 0.234
7 |
8 | Swivel : -0.185 0 0.055
9 | Center Hubcap : -0.211 0 0.037
10 | Center Wheel : -0.211 0 0.038
11 |
12 | Right Hubcap : 0 0.158 0.091
13 | Right Wheel : 0 0.158 0.091
14 |
15 | Left Hubcap : 0 -0.158 0.091
16 | Left Wheel : 0 -0.158 0.091
17 |
18 | Front Sonar : -0.2 0 0.209
19 | Back Sonar : 0.109 0 0.209
20 |
21 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/range/range_plugin.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/LinkState.msg:
--------------------------------------------------------------------------------
1 | # @todo: FIXME: sets pose and twist of a link. All children link poses/twists of the URDF tree are not updated accordingly, but should be.
2 | string link_name # link name, link_names are in gazebo scoped name notation, [model_name::body_name]
3 | geometry_msgs/Pose pose # desired pose in reference frame
4 | geometry_msgs/Twist twist # desired twist in reference frame
5 | string reference_frame # set pose/twist relative to the frame of this link/body
6 | # leave empty or "world" or "map" defaults to world-frame
7 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/p3d_test/test_double_pendulum.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/libcommon.sh:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 |
3 | # the function relocates all the ROS remappings in the command at the end of the
4 | # string this allows some punky uses of rosrun, for more information see:
5 | # https://github.com/ros-simulation/gazebo_ros_pkgs/issues/387
6 | relocate_remappings()
7 | {
8 | command_line=${1}
9 |
10 | for w in $command_line; do
11 | if $(echo "$w" | grep -q ':='); then
12 | ros_remaps="$ros_remaps $w"
13 | else
14 | gazebo_args="$gazebo_args $w"
15 | fi
16 | done
17 |
18 | echo "$gazebo_args$ros_remaps" | cut -c 1-
19 | }
20 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/set_model_state_test/set_model_state_test.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
9 |
10 |
11 |
12 |
--------------------------------------------------------------------------------
/gazebo_dev/cmake/gazebo_dev-extras.cmake:
--------------------------------------------------------------------------------
1 | # Depend on system install of Gazebo
2 | find_package(gazebo REQUIRED)
3 |
4 | message(STATUS "Gazebo version: ${GAZEBO_VERSION}")
5 |
6 | # The following lines will tell catkin to add the Gazebo directories and libraries to the
7 | # respective catkin_* cmake variables.
8 | set(gazebo_dev_INCLUDE_DIRS ${GAZEBO_INCLUDE_DIRS})
9 | set(gazebo_dev_LIBRARY_DIRS ${GAZEBO_LIBRARY_DIRS})
10 | set(gazebo_dev_LIBRARIES ${GAZEBO_LIBRARIES})
11 |
12 | # Append gazebo CXX_FLAGS to CMAKE_CXX_FLAGS (c++11)
13 | #set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${GAZEBO_CXX_FLAGS}")
14 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/GetLinkState.srv:
--------------------------------------------------------------------------------
1 | string link_name # name of link
2 | # link names are prefixed by model name, e.g. pr2::base_link
3 | string reference_frame # reference frame of returned information, must be a valid link
4 | # if empty, use inertial (gazebo world) frame
5 | # reference_frame names are prefixed by model name, e.g. pr2::base_link
6 | ---
7 | gazebo_msgs/LinkState link_state
8 | bool success # return true if get info is successful
9 | string status_message # comments if available
10 |
--------------------------------------------------------------------------------
/gazebo_plugins/cfg/GazeboRosCamera.cfg:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | PKG = 'gazebo_plugins'
4 | #import roslib; roslib.load_manifest(PKG)
5 |
6 | from dynamic_reconfigure.msg import SensorLevels
7 | #from dynamic_reconfigure.parameter_generator import *
8 | from dynamic_reconfigure.parameter_generator_catkin import *
9 | gen = ParameterGenerator()
10 | gen.add("imager_rate", double_t, SensorLevels.RECONFIGURE_CLOSE, \
11 | "Sets the frame rate of the imager. In externally triggered mode this must be more than trig_rate", 2, 1, 50)
12 |
13 | exit(gen.generate(PKG, "gazebo_ros_camera", "GazeboRosCamera"))
14 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SetLightProperties.srv:
--------------------------------------------------------------------------------
1 | string light_name # name of Gazebo Light
2 | bool cast_shadows
3 | std_msgs/ColorRGBA diffuse # diffuse color as red, green, blue, alpha
4 | std_msgs/ColorRGBA specular # specular color as red, green, blue, alpha
5 | float64 attenuation_constant
6 | float64 attenuation_linear
7 | float64 attenuation_quadratic
8 | geometry_msgs/Vector3 direction
9 | geometry_msgs/Pose pose # pose in world frame
10 | ---
11 | bool success # return true if get successful
12 | string status_message # comments if available
13 |
--------------------------------------------------------------------------------
/gazebo_plugins/cfg/GazeboRosOpenniKinect.cfg:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | PKG = 'gazebo_plugins'
4 | #import roslib; roslib.load_manifest(PKG)
5 |
6 | from dynamic_reconfigure.msg import SensorLevels
7 | #from dynamic_reconfigure.parameter_generator import *
8 | from dynamic_reconfigure.parameter_generator_catkin import *
9 | gen = ParameterGenerator()
10 | gen.add("imager_rate", double_t, SensorLevels.RECONFIGURE_CLOSE, \
11 | "Sets the frame rate of the imager. In externally triggered mode this must be more than trig_rate", 2, 1, 50)
12 |
13 | exit(gen.generate(PKG, "gazebo_ros_openni_kinect", "GazeboRosOpenniKinect"))
14 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/ContactState.msg:
--------------------------------------------------------------------------------
1 | string info # text info on this contact
2 | string collision1_name # name of contact collision1
3 | string collision2_name # name of contact collision2
4 | geometry_msgs/Wrench[] wrenches # list of forces/torques
5 | geometry_msgs/Wrench total_wrench # sum of forces/torques in every DOF
6 | geometry_msgs/Vector3[] contact_positions # list of contact position
7 | geometry_msgs/Vector3[] contact_normals # list of contact normals
8 | float64[] depths # list of penetration depths
9 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/camera.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
10 |
11 |
12 |
13 |
14 |
15 |
17 |
18 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/camera16bit.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
10 |
11 |
12 |
13 |
14 |
15 |
17 |
18 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/depth_camera.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
10 |
11 |
12 |
13 |
14 |
15 |
17 |
18 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/GetPhysicsProperties.srv:
--------------------------------------------------------------------------------
1 | ---
2 | # sets pose and twist of a link. All children link poses/twists of the URDF tree will be updated accordingly
3 | float64 time_step # dt in seconds
4 | bool pause # true if physics engine is paused
5 | float64 max_update_rate # throttle maximum physics update rate
6 | geometry_msgs/Vector3 gravity # gravity vector (e.g. earth ~[0,0,-9.81])
7 | gazebo_msgs/ODEPhysics ode_config # contains physics configurations pertaining to ODE
8 | bool success # return true if set wrench successful
9 | string status_message # comments if available
10 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/lcp_tests/balance.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/lcp_tests/stack.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/lcp_tests/stacks.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/spawn_model/spawn_box_file.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/perf:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 | final="$@"
3 |
4 | EXT=so
5 | if [ $(uname) = "Darwin" ]; then
6 | EXT=dylib
7 | fi
8 |
9 | # add ros plugin if does not exist
10 | if [ `expr "$final" : ".*libgazebo_ros_paths_plugin\.$EXT.*"` -eq 0 ]
11 | then
12 | final="$final -s `catkin_find --first-only libgazebo_ros_paths_plugin.$EXT`"
13 | fi
14 |
15 | if [ `expr "$final" : ".*libgazebo_ros_api_plugin\.$EXT.*"` -eq 0 ]
16 | then
17 | final="$final -s `catkin_find --first-only libgazebo_ros_api_plugin.$EXT`"
18 | fi
19 |
20 | setup_path=$(pkg-config --variable=prefix gazebo)/share/gazebo/
21 | . $setup_path/setup.sh && /usr/bin/valgrind --tool=callgrind gzserver $final
22 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/triggered_camera.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
10 |
11 |
12 |
13 |
14 |
15 |
17 |
18 |
--------------------------------------------------------------------------------
/gazebo_ros/test/ros_network/ros_network_disabled.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
15 |
16 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/ODEJointProperties.msg:
--------------------------------------------------------------------------------
1 | # access to low level joint properties, change these at your own risk
2 | float64[] damping # joint damping
3 | float64[] hiStop # joint limit
4 | float64[] loStop # joint limit
5 | float64[] erp # set joint erp
6 | float64[] cfm # set joint cfm
7 | float64[] stop_erp # set joint erp for joint limit "contact" joint
8 | float64[] stop_cfm # set joint cfm for joint limit "contact" joint
9 | float64[] fudge_factor # joint fudge_factor applied at limits, see ODE manual for info.
10 | float64[] fmax # ode joint param fmax
11 | float64[] vel # ode joint param vel
12 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/GetJointProperties.srv:
--------------------------------------------------------------------------------
1 | string joint_name # name of joint
2 | ---
3 | # joint type
4 | uint8 type
5 | uint8 REVOLUTE = 0 # single DOF
6 | uint8 CONTINUOUS = 1 # single DOF (revolute w/o joints)
7 | uint8 PRISMATIC = 2 # single DOF
8 | uint8 FIXED = 3 # 0 DOF
9 | uint8 BALL = 4 # 3 DOF
10 | uint8 UNIVERSAL = 5 # 2 DOF
11 | # dynamics properties
12 | float64[] damping
13 | # joint state
14 | float64[] position
15 | float64[] rate
16 | # service return status
17 | bool success # return true if get successful
18 | string status_message # comments if available
19 |
--------------------------------------------------------------------------------
/gazebo_ros/launch/mud_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/gazebo_ros/launch/rubble_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/gazebo_ros/launch/shapes_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/launch/tricycle.urdf.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
--------------------------------------------------------------------------------
/gazebo_plugins/scripts/test_range.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | import rospy
3 | from sensor_msgs.msg import Range
4 |
5 | import unittest
6 |
7 | class TestRangePlugin(unittest.TestCase):
8 |
9 | def test_max_range(self):
10 | msg = rospy.wait_for_message('/sonar2', Range)
11 | self.assertAlmostEqual(msg.range, msg.max_range)
12 |
13 | def test_inside_range(self):
14 | msg = rospy.wait_for_message('/sonar', Range)
15 | self.assertTrue(msg.range < 0.25 and msg.range > 0.22, 'actual value: {0}'.format(msg.range))
16 |
17 | if __name__ == '__main__':
18 | import rostest
19 | PKG_NAME = 'gazebo_plugins'
20 | TEST_NAME = PKG_NAME + 'range_test'
21 | rospy.init_node(TEST_NAME)
22 | rostest.rosrun(PKG_NAME, TEST_NAME, TestRangePlugin)
23 |
--------------------------------------------------------------------------------
/gazebo_ros/launch/willowgarage_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/spawn_model/spawn_box_param.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/debug:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 | final="$@"
3 |
4 | EXT=so
5 | if [ $(uname) = "Darwin" ]; then
6 | EXT=dylib
7 | fi
8 |
9 | # add ros path plugin if it does not already exist in the passed in arguments
10 | if [ `expr "$final" : ".*libgazebo_ros_paths_plugin\.$EXT.*"` -eq 0 ]
11 | then
12 | final="$final -s `catkin_find --first-only libgazebo_ros_paths_plugin.$EXT`"
13 | fi
14 |
15 | # add ros api plugin if it does not already exist in the passed in arguments
16 | if [ `expr "$final" : ".*libgazebo_ros_api_plugin\.$EXT.*"` -eq 0 ]
17 | then
18 | final="$final -s `catkin_find --first-only libgazebo_ros_api_plugin.$EXT`"
19 | fi
20 |
21 | setup_path=$(pkg-config --variable=prefix gazebo)/share/gazebo/
22 | . $setup_path/setup.sh && rosrun gazebo_ros gdbrun gzserver $final
23 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/GetModelProperties.srv:
--------------------------------------------------------------------------------
1 | string model_name # name of Gazebo Model
2 | ---
3 | string parent_model_name # parent model
4 | string canonical_body_name # name of canonical body, body names are prefixed by model name, e.g. pr2::base_link
5 | string[] body_names # list of bodies, body names are prefixed by model name, e.g. pr2::base_link
6 | string[] geom_names # list of geoms
7 | string[] joint_names # list of joints attached to the model
8 | string[] child_model_names # list of child models
9 | bool is_static # returns true if model is static
10 | bool success # return true if get successful
11 | string status_message # comments if available
12 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/urdf/box.urdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 | Gazebo/Blue
24 |
25 |
26 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/p3d_test/test_3_single_pendulums.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
--------------------------------------------------------------------------------
/gazebo_plugins/cfg/WheelSlip.cfg:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 |
3 | # Wheel slip plugin configuration
4 |
5 | PACKAGE='gazebo_plugins'
6 |
7 | from dynamic_reconfigure.parameter_generator_catkin import *
8 |
9 | gen = ParameterGenerator()
10 |
11 | # Name Type Reconf level Description Default Min Max
12 | gen.add("slip_compliance_unitless_lateral", double_t, 0, "Unitless slip compliance (slip / friction) in the lateral direction.", -1.0, -1.0, 20.0)
13 | gen.add("slip_compliance_unitless_longitudinal", double_t, 0, "Unitless slip compliance (slip / friction) in the longitudinal direction.", -1.0, -1.0, 20.0)
14 |
15 | exit(gen.generate(PACKAGE, "wheel_slip", "WheelSlip"))
16 |
--------------------------------------------------------------------------------
/gazebo_plugins/src/gazebo_plugins/gazebo_plugins_interface.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | # Wrappers around the services provided by gazebo_ros_factory plugin
3 |
4 | import roslib; roslib.load_manifest('gazebo_plugins')
5 |
6 | import sys
7 |
8 | import rospy
9 | from gazebo_plugins.msg import GazeboModel
10 | from gazebo_plugins.srv import SpawnModel
11 | from gazebo_plugins.srv import DeleteModel
12 | from geometry_msgs.msg import Pose, Point, Quaternion
13 |
14 | def load_model(model_msg):
15 | print('waiting for service spawn_model')
16 | rospy.wait_for_service('spawn_model')
17 | try:
18 | spawn_model= rospy.ServiceProxy('spawn_model', SpawnModel)
19 | resp1 = spawn_model(model_msg)
20 | return resp1.success
21 | except rospy.ServiceException as e:
22 | print("Service call failed: %s" % e)
23 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SpawnModel.srv:
--------------------------------------------------------------------------------
1 | string model_name # name of the model to be spawn
2 | string model_xml # this should be an urdf or gazebo xml
3 | string robot_namespace # spawn robot and all ROS interfaces under this namespace
4 | geometry_msgs/Pose initial_pose # only applied to canonical body
5 | string reference_frame # initial_pose is defined relative to the frame of this model/body
6 | # if left empty or "world", then gazebo world frame is used
7 | # if non-existent model/body is specified, an error is returned
8 | # and the model is not spawned
9 | ---
10 | bool success # return true if spawn successful
11 | string status_message # comments if available
12 |
--------------------------------------------------------------------------------
/gazebo_ros/test/ros_network/ros_network_default.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
19 |
20 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/ODEPhysics.msg:
--------------------------------------------------------------------------------
1 | bool auto_disable_bodies # enable auto disabling of bodies, default false
2 | uint32 sor_pgs_precon_iters # preconditioning inner iterations when uisng projected Gauss Seidel
3 | uint32 sor_pgs_iters # inner iterations when uisng projected Gauss Seidel
4 | float64 sor_pgs_w # relaxation parameter when using projected Gauss Seidel, 1 = no relaxation
5 | float64 sor_pgs_rms_error_tol # rms error tolerance before stopping inner iterations
6 | float64 contact_surface_layer # contact "dead-band" width
7 | float64 contact_max_correcting_vel # contact maximum correction velocity
8 | float64 cfm # global constraint force mixing
9 | float64 erp # global error reduction parameter
10 | uint32 max_contacts # maximum contact joints between two geoms
11 |
--------------------------------------------------------------------------------
/gazebo_ros/test/ros_network/no_gazebo_network_api.yaml:
--------------------------------------------------------------------------------
1 | strict: true
2 |
3 | ##########################################################
4 | # Published topics
5 | topics:
6 | # System
7 | - topic: /clock
8 | type: rosgraph_msgs/Clock
9 | num_publishers: 1
10 | num_subscribers: -1
11 |
12 | - topic: /rosout
13 | type: rosgraph_msgs/Log
14 | num_publishers: -1
15 | num_subscribers: -1
16 |
17 | ##########################################################
18 | # Published services
19 | services:
20 | # System
21 | - service: /gazebo/set_logger_level
22 | type: roscpp/SetLoggerLevel
23 |
24 | - service: /gazebo/get_loggers
25 | type: roscpp/GetLoggers
26 |
27 | - service: /ros_network_by_default/get_loggers
28 | type: roscpp/GetLoggers
29 |
30 | - service: /ros_network_by_default/set_logger_level
31 | type: roscpp/SetLoggerLevel
32 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/spawn_test/spawn_robots.sh:
--------------------------------------------------------------------------------
1 | # Required: rrtbot_description package
2 |
3 | read -p "URDF from file:"
4 | rosrun gazebo_ros spawn_model -file `rospack find rrbot_description`/urdf/rrbot.xml -urdf -y 1 -model rrbot1 -robot_namespace robot2
5 |
6 | read -p "URDF from parameter server using roslaunch and xacro:"
7 | roslaunch parameter_server_test.launch
8 |
9 | read -p "SDF from local model database:"
10 | rosrun gazebo_ros spawn_model -file `echo $GAZEBO_MODEL_PATH`/coke_can/model.sdf -sdf -model coke_can1 -y 0.2 -x -0.3
11 |
12 | read -p "SDF from local model database with Deprecated tag:"
13 | rosrun gazebo_ros spawn_model -file `echo $GAZEBO_MODEL_PATH`/coke_can/model.sdf -gazebo -model coke_can2 -y 1.2 -x -0.3
14 |
15 | read -p "SDF from the online model database:"
16 | rosrun gazebo_ros spawn_model -database coke_can -sdf -model coke_can3 -y 2.2 -x -0.3
17 |
18 |
19 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/ApplyJointEffort.srv:
--------------------------------------------------------------------------------
1 | # set urdf joint effort
2 | string joint_name # joint to apply wrench (linear force and torque)
3 | float64 effort # effort to apply
4 | time start_time # optional wrench application start time (seconds)
5 | # if start_time < current time, start as soon as possible
6 | duration duration # optional duration of wrench application time (seconds)
7 | # if duration < 0, apply wrench continuously without end
8 | # if duration = 0, do nothing
9 | # if duration < step size, assume step size and
10 | # display warning in status_message
11 | ---
12 | bool success # return true if effort application is successful
13 | string status_message # comments if available
14 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/GetLinkProperties.srv:
--------------------------------------------------------------------------------
1 | string link_name # name of link
2 | # link names are prefixed by model name, e.g. pr2::base_link
3 | ---
4 | geometry_msgs/Pose com # center of mass location in link frame
5 | # and orientation of the moment of inertias
6 | # relative to the link frame
7 | bool gravity_mode # set gravity mode on/off
8 | float64 mass # linear mass of link
9 | float64 ixx # moment of inertia
10 | float64 ixy # moment of inertia
11 | float64 ixz # moment of inertia
12 | float64 iyy # moment of inertia
13 | float64 iyz # moment of inertia
14 | float64 izz # moment of inertia
15 | bool success # return true if get info is successful
16 | string status_message # comments if available
17 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/SetLinkProperties.srv:
--------------------------------------------------------------------------------
1 | string link_name # name of link
2 | # link names are prefixed by model name, e.g. pr2::base_link
3 | geometry_msgs/Pose com # center of mass location in link frame
4 | # and orientation of the moment of inertias
5 | # relative to the link frame
6 | bool gravity_mode # set gravity mode on/off
7 | float64 mass # linear mass of link
8 | float64 ixx # moment of inertia
9 | float64 ixy # moment of inertia
10 | float64 ixz # moment of inertia
11 | float64 iyy # moment of inertia
12 | float64 iyz # moment of inertia
13 | float64 izz # moment of inertia
14 | ---
15 | bool success # return true if get info is successful
16 | string status_message # comments if available
17 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/materials.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/materials.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
--------------------------------------------------------------------------------
/gazebo_ros/test/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | set (rostests_python
2 | ros_network/ros_network_default.test
3 | ros_network/ros_network_disabled.test
4 | )
5 |
6 | if(CATKIN_ENABLE_TESTING)
7 | find_package(rostest REQUIRED)
8 | foreach (rostest ${rostests_python})
9 | # We don't set a timeout here because we trust rostest to enforce the
10 | # timeout specified in each .test file.
11 | add_rostest(${rostest} rostest ${CMAKE_CURRENT_SOURCE_DIR}/${rostest})
12 | # Check for test result file and create one if needed. rostest can fail to
13 | # generate a file if it throws an exception.
14 | add_test(check_${rostest} rosrun rosunit check_test_ran.py
15 | --rostest ${ROS_PACKAGE_NAME} ${CMAKE_CURRENT_SOURCE_DIR}/${rostest})
16 | endforeach()
17 | endif()
18 |
19 | install(PROGRAMS
20 | ros_network/ros_api_checker
21 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/test
22 | )
23 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/urdf/cube.urdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 | Gazebo/GrayGrid
25 | false
26 |
27 |
28 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/launch/tricycle.gazebo.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/launch/pioneer3dx.gazebo.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/large_models/smaller_large_model.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/GetModelState.srv:
--------------------------------------------------------------------------------
1 | string model_name # name of Gazebo Model
2 | string relative_entity_name # return pose and twist relative to this entity
3 | # an entity can be a model, body, or geom
4 | # be sure to use gazebo scoped naming notation (e.g. [model_name::body_name])
5 | # leave empty or "world" will use inertial world frame
6 | ---
7 | Header header # Standard metadata for higher-level stamped data types.
8 | # * header.seq holds the number of requests since the plugin started
9 | # * header.stamp timestamp related to the pose
10 | # * header.frame_id not used but currently filled with the relative_entity_name
11 | geometry_msgs/Pose pose # pose of model in relative entity frame
12 | geometry_msgs/Twist twist # twist of model in relative entity frame
13 | bool success # return true if get successful
14 | string status_message # comments if available
15 |
--------------------------------------------------------------------------------
/gazebo_ros/launch/range_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/launch/multi_robot_scenario.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
22 |
23 |
25 |
26 |
27 |
28 |
29 |
30 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/large_models/large_model.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
23 |
24 |
25 |
26 |
27 |
28 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/launch/tricycle_drive_scenario.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
29 |
30 |
31 |
32 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
--------------------------------------------------------------------------------
/gazebo_dev/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | gazebo_dev
4 | 2.9.3
5 |
6 | Provides a cmake config for the default version of Gazebo for the ROS distribution.
7 |
8 |
9 | Alejandro Hernández Cordero
10 |
11 | Apache 2.0
12 |
13 | http://gazebosim.org/tutorials?cat=connect_ros
14 | https://github.com/ros-simulation/gazebo_ros_pkgs/issues
15 | https://github.com/ros-simulation/gazebo_ros_pkgs
16 |
17 | Dave Coleman
18 | John Hsu
19 | Johannes Meyer
20 |
21 | catkin
22 |
23 | libgazebo11-dev
24 | gazebo11
25 |
26 |
27 | This package has been deprecated as of January 2025 with Gazebo classic 11 reaching
28 | end-of-life. Users are highly encouraged to migrate to the new Gazebo
29 | using our migration guides (https://gazebosim.org/docs/latest/gazebo_classic_migration)
30 |
31 |
32 |
33 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
38 |
39 |
40 |
41 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # gazebo_ros_pkgs
2 |
3 | > [!WARNING]
4 | >
5 | > ## Deprecation
6 | >
7 | > This package has been deprecated as of January 2025 with Gazebo classic 11
8 | > reaching end-of-life. Users are highly encouraged to migrate to the new Gazebo
9 | > using our
10 | > [migration guides](https://gazebosim.org/docs/latest/gazebo_classic_migration).
11 | > The Gazebo team will no longer provide direct support of this package, triage
12 | > issues, or merge pull requests. If you need help with using this package,
13 | > please post your question on with the
14 | > `gazebo` tag.
15 |
16 | [](http://build.ros.org/job/Kpr__gazebo_ros_pkgs__ubuntu_xenial_amd64)
17 |
18 | Wrappers, tools and additional API's for using ROS with the Gazebo simulator. Formally simulator_gazebo stack, gazebo_pkgs is a meta package. Now Catkinized and works with the standalone Gazebo debian.
19 |
20 | ### Installation
21 | [Installing gazebo_ros_pkgs](http://gazebosim.org/tutorials?tut=ros_installing&cat=connect_ros)
22 |
23 | ### Documentation and Tutorials
24 | [On gazebosim.org](http://gazebosim.org/tutorials?cat=connect_ros)
25 |
26 | ### Develop and Contribute
27 |
28 | See [Contribute](https://github.com/ros-simulation/gazebo_ros_pkgs/blob/hydro-devel/CONTRIBUTING.md) page.
29 |
30 |
31 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
20 |
21 |
22 |
23 |
24 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/p3d_test/test_3_double_pendulums.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro:
--------------------------------------------------------------------------------
1 |
2 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
38 |
39 |
40 |
41 |
42 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
--------------------------------------------------------------------------------
/gazebo_ros_pkgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | gazebo_ros_pkgs
4 | 2.9.3
5 | Interface for using ROS with the Gazebo simulator.
6 |
7 | Alejandro Hernández Cordero
8 | Jose Luis Rivero
9 |
10 | BSD,LGPL,Apache 2.0
11 |
12 | http://gazebosim.org/tutorials?cat=connect_ros
13 | https://github.com/ros-simulation/gazebo_ros_pkgs/issues
14 | https://github.com/ros-simulation/gazebo_ros_pkgs
15 |
16 | John Hsu, Nate Koenig, Dave Coleman
17 |
18 | catkin
19 |
20 | gazebo_dev
21 | gazebo_msgs
22 | gazebo_plugins
23 | gazebo_ros
24 |
25 |
26 |
27 |
28 | This package has been deprecated as of January 2025 with Gazebo classic 11 reaching
29 | end-of-life. Users are highly encouraged to migrate to the new Gazebo
30 | using our migration guides (https://gazebosim.org/docs/latest/gazebo_classic_migration)
31 |
32 |
33 |
34 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/gzclient:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 | [ -L ${0} ] && SCRIPT_DIR=$(readlink ${0}) || SCRIPT_DIR=${0}
3 | SCRIPT_DIR=$(dirname ${SCRIPT_DIR})
4 |
5 | . ${SCRIPT_DIR}/libcommon.sh
6 |
7 | final="$@"
8 |
9 | EXT=so
10 | if [ $(uname) = "Darwin" ]; then
11 | EXT=dylib
12 | fi
13 |
14 | # add ros plugin if does not exist
15 | if [ `expr "$final" : ".*libgazebo_ros_paths_plugin\.$EXT.*"` -eq 0 ]
16 | then
17 | final="$final -g `catkin_find --first-only libgazebo_ros_paths_plugin.$EXT`"
18 | fi
19 |
20 | # add ros api plugin if it does not already exist in the passed in arguments
21 | if [ `expr "$final" : ".*libgazebo_ros_api_plugin\.$EXT.*"` -eq 0 ]
22 | then
23 | final="$final -g `catkin_find --first-only libgazebo_ros_api_plugin.$EXT`"
24 | fi
25 |
26 | setup_path=$(pkg-config --variable=prefix gazebo)/share/gazebo/
27 |
28 | # source setup.sh, but keep local modifications to GAZEBO_MASTER_URI and GAZEBO_MODEL_DATABASE_URI
29 | desired_master_uri="$GAZEBO_MASTER_URI"
30 | desired_model_database_uri="$GAZEBO_MODEL_DATABASE_URI"
31 | . $setup_path/setup.sh
32 | if [ "$desired_master_uri" = "" ]; then
33 | desired_master_uri="$GAZEBO_MASTER_URI"
34 | fi
35 | if [ "$desired_model_database_uri" = "" ]; then
36 | desired_model_database_uri="$GAZEBO_MODEL_DATABASE_URI"
37 | fi
38 |
39 | final=$(relocate_remappings "${final}")
40 |
41 | # Combine the commands
42 | GAZEBO_MASTER_URI="$desired_master_uri" GAZEBO_MODEL_DATABASE_URI="$desired_model_database_uri" gzclient $final
43 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/gzserver:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 | [ -L ${0} ] && SCRIPT_DIR=$(readlink ${0}) || SCRIPT_DIR=${0}
3 | SCRIPT_DIR=$(dirname ${SCRIPT_DIR})
4 |
5 | . ${SCRIPT_DIR}/libcommon.sh
6 |
7 | final="$@"
8 |
9 | EXT=so
10 | if [ $(uname) = "Darwin" ]; then
11 | EXT=dylib
12 | fi
13 |
14 | # add ros path plugin if it does not already exist in the passed in arguments
15 | if [ `expr "$final" : ".*libgazebo_ros_paths_plugin\.$EXT.*"` -eq 0 ]
16 | then
17 | final="$final -s `catkin_find --first-only libgazebo_ros_paths_plugin.$EXT`"
18 | fi
19 |
20 | # add ros api plugin if it does not already exist in the passed in arguments
21 | if [ `expr "$final" : ".*libgazebo_ros_api_plugin\.$EXT.*"` -eq 0 ]
22 | then
23 | final="$final -s `catkin_find --first-only libgazebo_ros_api_plugin.$EXT`"
24 | fi
25 |
26 | setup_path=$(pkg-config --variable=prefix gazebo)/share/gazebo/
27 |
28 | # source setup.sh, but keep local modifications to GAZEBO_MASTER_URI and GAZEBO_MODEL_DATABASE_URI
29 | desired_master_uri="$GAZEBO_MASTER_URI"
30 | desired_model_database_uri="$GAZEBO_MODEL_DATABASE_URI"
31 | . $setup_path/setup.sh
32 | if [ "$desired_master_uri" = "" ]; then
33 | desired_master_uri="$GAZEBO_MASTER_URI"
34 | fi
35 | if [ "$desired_model_database_uri" = "" ]; then
36 | desired_model_database_uri="$GAZEBO_MODEL_DATABASE_URI"
37 | fi
38 |
39 | final=$(relocate_remappings "${final}")
40 |
41 | GAZEBO_MASTER_URI="$desired_master_uri" GAZEBO_MODEL_DATABASE_URI="$desired_model_database_uri" gzserver $final
42 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/config/example_models.yaml:
--------------------------------------------------------------------------------
1 | gazebo_models: # everything here is namespaced under "gazebo_models"
2 | pr2: # model name used inside gazebo
3 | specification: robot_description # potentially contains:
4 | # 1. a verbatim string with URDF or Gazebo Model XML or
5 | # 2. a parameter name that refers to a parameter containing (1.)
6 | # the spawner will differentiate automatically
7 | namespace: / # namespace for gazebo_ros_plugins related to this model
8 | initial_pose: # initial pose for the model
9 | x: 0
10 | y: 0
11 | z: 0
12 | rx: 0
13 | ry: 0
14 | rz: 0
15 | joint_name: r_forearm_link # name of the joint to set initial position
16 | position: 1.57 # initial joint position
17 | joint_name: head_pan_link # name of the joint to set initial position
18 | position: 0.78 # initial joint position
19 |
20 | # another example
21 | table:
22 | specification: table_description
23 | namespace: /table
24 | initial_pose:
25 | x: 1
26 | y: 0
27 | z: 0
28 | rx: 0
29 | ry: 0
30 | rz: 0
31 |
32 |
--------------------------------------------------------------------------------
/gazebo_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.0.2)
2 | project(gazebo_msgs)
3 |
4 | find_package(catkin REQUIRED COMPONENTS
5 | std_msgs
6 | trajectory_msgs
7 | geometry_msgs
8 | sensor_msgs
9 | std_srvs
10 | message_generation
11 | )
12 |
13 | add_message_files(
14 | DIRECTORY msg
15 | FILES
16 | ContactsState.msg
17 | ContactState.msg
18 | LinkState.msg
19 | LinkStates.msg
20 | ModelState.msg
21 | ModelStates.msg
22 | ODEJointProperties.msg
23 | ODEPhysics.msg
24 | PerformanceMetrics.msg
25 | SensorPerformanceMetric.msg
26 | WorldState.msg
27 | )
28 |
29 | add_service_files(DIRECTORY srv FILES
30 | ApplyBodyWrench.srv
31 | DeleteModel.srv
32 | DeleteLight.srv
33 | GetLinkState.srv
34 | GetPhysicsProperties.srv
35 | SetJointProperties.srv
36 | SetModelConfiguration.srv
37 | SpawnModel.srv
38 | ApplyJointEffort.srv
39 | GetJointProperties.srv
40 | GetModelProperties.srv
41 | GetWorldProperties.srv
42 | SetLinkProperties.srv
43 | SetModelState.srv
44 | BodyRequest.srv
45 | GetLinkProperties.srv
46 | GetModelState.srv
47 | JointRequest.srv
48 | SetLinkState.srv
49 | SetPhysicsProperties.srv
50 | SetJointTrajectory.srv
51 | GetLightProperties.srv
52 | SetLightProperties.srv
53 | )
54 |
55 | generate_messages(DEPENDENCIES
56 | std_msgs
57 | geometry_msgs
58 | sensor_msgs
59 | trajectory_msgs
60 | )
61 |
62 | catkin_package(
63 | CATKIN_DEPENDS
64 | message_runtime
65 | std_msgs
66 | trajectory_msgs
67 | geometry_msgs
68 | sensor_msgs
69 | std_srvs
70 | )
71 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_body.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
38 |
39 |
--------------------------------------------------------------------------------
/CONTRIBUTING.md:
--------------------------------------------------------------------------------
1 | # How to Contribute
2 |
3 | We welcome contributions to this repo and encourage you to fork the project, thanks!
4 |
5 | ## Implementations of simulations
6 |
7 | It is highly recommended to place the code that performs simulation inside
8 | [upstream gazebo code](https://bitbucket.org/osrf/gazebo/). The Gazebo project
9 | provides documentation about [how to create and code
10 | plugins](http://gazebosim.org/tutorials?cat=write_plugin) Ideally
11 | gazebo_ros_pkgs should implement the ROS wrapper over an existing gazebo
12 | plugin.
13 |
14 | ## Issues and Pull Requests
15 |
16 | There are several maintainers of different packages in this repository. If you
17 | are submitting an issue or a pull request, please prefix the title of the issue
18 | or pull resquest with the package name. This way the appropriate maintainers
19 | can more easily recognize contributions which require their attention.
20 |
21 | ## Style
22 |
23 | We follow the [C++ ROS style guidelines](http://ros.org/wiki/CppStyleGuide) and
24 | conventions as closely as possible. However, because the plugins inherit from Gazebo
25 | classes and Gazebo follows a very different formatting standard, there are a few
26 | exceptions where Gazebo's function names do not comply to the ROS guidelines.
27 |
28 | ## Tests
29 |
30 | We encourage developers to include tests in their pull requests when possible,
31 | both for bug fixes and new features.
32 | Examples of tests are in the `gazebo_plugins/test*` folders.
33 | Currently the tests must not be run in parallel (see issue
34 | [issue 409](https://github.com/ros-simulation/gazebo_ros_pkgs/issues/409))
35 | so it is recommented to use the `-j1` argument to `catkin run_tests`.
36 |
--------------------------------------------------------------------------------
/gazebo_ros_control/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | gazebo_ros_control
4 | 2.9.3
5 | gazebo_ros_control
6 |
7 | Alejandro Hernández Cordero
8 | Jose Luis Rivero
9 |
10 | BSD
11 |
12 | http://ros.org/wiki/gazebo_ros_control
13 | https://github.com/ros-simulation/gazebo_ros_pkgs/issues
14 | https://github.com/ros-simulation/gazebo_ros_pkgs
15 |
16 | Jonathan Bohren
17 | Dave Coleman
18 |
19 | catkin
20 |
21 | gazebo_dev
22 | gazebo_ros
23 | roscpp
24 | std_msgs
25 | control_toolbox
26 | controller_manager
27 | pluginlib
28 | hardware_interface
29 | transmission_interface
30 | joint_limits_interface
31 | urdf
32 | angles
33 |
34 |
35 |
36 |
37 | This package has been deprecated as of January 2025 with Gazebo classic 11 reaching
38 | end-of-life. Users are highly encouraged to migrate to the new Gazebo
39 | using our migration guides (https://gazebosim.org/docs/latest/gazebo_classic_migration)
40 |
41 |
42 |
43 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_template.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (C) 2012-2014 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 | /*
18 | * Desc: 3D position interface.
19 | * Author: Sachin Chitta and John Hsu
20 | * Date: 10 June 2008
21 | */
22 |
23 | #ifndef GAZEBO_ROS_TEMPLATE_HH
24 | #define GAZEBO_ROS_TEMPLATE_HH
25 |
26 | #include
27 |
28 | #include
29 | #include
30 | #include
31 | #include
32 | #include
33 |
34 | namespace gazebo
35 | {
36 |
37 | class GazeboRosTemplate : public ModelPlugin
38 | {
39 | /// \brief Constructor
40 | public: GazeboRosTemplate();
41 |
42 | /// \brief Destructor
43 | public: virtual ~GazeboRosTemplate();
44 |
45 | /// \brief Load the controller
46 | public: void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
47 |
48 | /// \brief Update the controller
49 | protected: virtual void UpdateChild();
50 |
51 | };
52 |
53 | }
54 |
55 | #endif
56 |
57 |
--------------------------------------------------------------------------------
/gazebo_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | gazebo_msgs
4 | 2.9.3
5 |
6 | Message and service data structures for interacting with Gazebo from ROS.
7 |
8 |
9 | Alejandro Hernández Cordero
10 | Jose Luis Rivero
11 |
12 | BSD
13 |
14 | http://gazebosim.org/tutorials?cat=connect_ros
15 | https://github.com/ros-simulation/gazebo_ros_pkgs/issues
16 | https://github.com/ros-simulation/gazebo_ros_pkgs
17 |
18 | John Hsu
19 |
20 | catkin
21 |
22 | geometry_msgs
23 | sensor_msgs
24 | trajectory_msgs
25 | std_msgs
26 | std_srvs
27 | message_generation
28 |
29 | geometry_msgs
30 | sensor_msgs
31 | trajectory_msgs
32 | std_msgs
33 | message_runtime
34 | std_srvs
35 |
36 |
37 | This package has been deprecated as of January 2025 with Gazebo classic 11 reaching
38 | end-of-life. Users are highly encouraged to migrate to the new Gazebo
39 | using our migration guides (https://gazebosim.org/docs/latest/gazebo_classic_migration)
40 |
41 |
42 |
43 |
44 |
45 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_plugins.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 | chassis_swivel_joint, swivel_wheel_joint, left_hub_joint, right_hub_joint
9 | 10.0
10 | true
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 | Debug
19 |
20 | false
21 | true
22 | true
23 | left_hub_joint
24 | right_hub_joint
25 | 0.3
26 | 0.18
27 | 20
28 | 1.8
29 | cmd_vel
30 | odom
31 | odom
32 | world
33 | base_link
34 | 10.0
35 |
36 |
37 |
38 |
39 |
40 |
--------------------------------------------------------------------------------
/gazebo_msgs/msg/WorldState.msg:
--------------------------------------------------------------------------------
1 | # This is a message that holds data necessary to reconstruct a snapshot of the world
2 | #
3 | # = Approach to Message Passing =
4 | # The state of the world is defined by either
5 | # 1. Inertial Model pose, twist
6 | # * kinematic data - connectivity graph from Model to each Link
7 | # * joint angles
8 | # * joint velocities
9 | # * Applied forces - Body wrench
10 | # * relative transform from Body to each collision Geom
11 | # Or
12 | # 2. Inertial (absolute) Body pose, twist, wrench
13 | # * relative transform from Body to each collision Geom - constant, so not sent over wire
14 | # * back compute from canonical body info to get Model pose and twist.
15 | #
16 | # Chooing (2.) because it matches most physics engines out there
17 | # and is simpler.
18 | #
19 | # = Future =
20 | # Consider impacts on using reduced coordinates / graph (parent/child links) approach
21 | # constraint and physics solvers.
22 | #
23 | # = Application =
24 | # This message is used to do the following:
25 | # * reconstruct the world and objects for sensor generation
26 | # * stop / start simulation - need pose, twist, wrench of each body
27 | # * collision detection - need pose of each collision geometry. velocity/acceleration if
28 | #
29 | # = Assumptions =
30 | # Assuming that each (physics) processor node locally already has
31 | # * collision information - Trimesh for Geoms, etc
32 | # * relative transforms from Body to Geom - this is assumed to be fixed, do not send oved wire
33 | # * inertial information - does not vary in time
34 | # * visual information - does not vary in time
35 | #
36 |
37 | Header header
38 |
39 | string[] name
40 | geometry_msgs/Pose[] pose
41 | geometry_msgs/Twist[] twist
42 | geometry_msgs/Wrench[] wrench
43 |
--------------------------------------------------------------------------------
/gazebo_msgs/srv/ApplyBodyWrench.srv:
--------------------------------------------------------------------------------
1 | # Apply Wrench to Gazebo Body.
2 | # via the callback mechanism
3 | # all Gazebo operations are made in world frame
4 | string body_name # Gazebo body to apply wrench (linear force and torque)
5 | # wrench is applied in the gazebo world by default
6 | # body names are prefixed by model name, e.g. pr2::base_link
7 | string reference_frame # wrench is defined in the reference frame of this entity
8 | # use inertial frame if left empty
9 | # frame names are bodies prefixed by model name, e.g. pr2::base_link
10 | geometry_msgs/Point reference_point # wrench is defined at this location in the reference frame
11 | geometry_msgs/Wrench wrench # wrench applied to the origin of the body
12 | time start_time # (optional) wrench application start time (seconds)
13 | # if start_time is not specified, or
14 | # start_time < current time, start as soon as possible
15 | duration duration # optional duration of wrench application time (seconds)
16 | # if duration < 0, apply wrench continuously without end
17 | # if duration = 0, do nothing
18 | # if duration < step size, apply wrench
19 | # for one step size
20 | ---
21 | bool success # return true if set wrench successful
22 | string status_message # comments if available
23 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_plugins.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 | Debug
9 |
10 | false
11 | true
12 | true
13 | front_steering_joint
14 | front_wheel_joint
15 | left_wheel_joint
16 | right_wheel_joint
17 | 0.135
18 | 0.135
19 | 0.548
20 | cmd_vel
21 | odom
22 | odom
23 | encoder
24 | base_link
25 | 10.0
26 | 1.8
27 | 5.0
28 | 0.05
29 | 20
30 | 0.4
31 | 0.02
32 |
33 |
34 |
35 |
36 |
37 |
--------------------------------------------------------------------------------
/gazebo_plugins/Media/models/chair/doc.kml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | Chair
5 | Google SketchUp 7.0.8657]]>
6 | SketchUp
7 | 1
8 |
9 | 320.223
10 | 64.7271
11 | 40.01698901172049
12 | -105.2829857471169
13 | 2.891488298910991
14 | 1.320883614486943
15 |
16 |
17 | Tour
18 |
19 |
20 | 1
21 |
22 | 320.223
23 | 64.7271
24 | 40.01698901172049
25 | -105.2829857471169
26 | 2.891488298910991
27 | 1.320883614486943
28 |
29 |
30 |
31 |
32 | Model
33 |
34 |
36 |
37 | relativeToGround
38 |
39 | -105.283000000000
40 | 40.017000000000
41 | 0.000000000000
42 |
43 |
44 | 0
45 | 0
46 | 0
47 |
48 |
49 | 1.0
50 | 1.0
51 | 1.0
52 |
53 |
54 | models/Chair.dae
55 |
56 |
57 |
58 |
59 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/large_models/large_models.world:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
--------------------------------------------------------------------------------
/gazebo_plugins/scripts/test_block_laser_clipping.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | """
4 | Test plugin gazebo_ros_block_laser using gazebo_ros_block_laser_clipping.world.
5 | """
6 |
7 | import math
8 | import rospy
9 | from sensor_msgs.msg import PointCloud
10 |
11 | import unittest
12 |
13 | class TestBlockLaserClippingPlugin(unittest.TestCase):
14 | MIN_RANGE = 0.4
15 | MAX_RANGE = 1.0
16 |
17 | def _ranges(self):
18 | msg = rospy.wait_for_message('test_block_laser', PointCloud)
19 | for point in msg.points:
20 | yield math.sqrt(point.x**2 + point.y**2 + point.z**2)
21 |
22 | def test_points_at_all_depths(self):
23 | # Make sure there are points at all depths
24 | BIN_SIZE = 0.01
25 | num_bins = int((self.MAX_RANGE - self.MIN_RANGE) / BIN_SIZE)
26 | bins = [b * BIN_SIZE + self.MIN_RANGE for b in range(num_bins)]
27 | bin_counts = dict(zip(bins, [0] * len(bins)))
28 |
29 | for r in self._ranges():
30 | closest_bin = None
31 | closest_dist = float('inf')
32 | for b in bins:
33 | dist = abs(r - b)
34 | if abs(r - b) < closest_dist:
35 | closest_dist = dist
36 | closest_bin = b
37 | bin_counts[closest_bin] += 1
38 |
39 | self.assertTrue(0 not in bin_counts.values(), msg=repr(bin_counts))
40 |
41 | def test_between_min_max(self):
42 | ALLOWED_ERROR = 0.00001
43 | for r in self._ranges():
44 | self.assertGreater(r, self.MIN_RANGE - ALLOWED_ERROR)
45 | self.assertLess(r, self.MAX_RANGE + ALLOWED_ERROR)
46 |
47 |
48 | if __name__ == '__main__':
49 | import rostest
50 | PKG_NAME = 'gazebo_plugins'
51 | TEST_NAME = PKG_NAME + 'block_laser_clipping'
52 | rospy.init_node(TEST_NAME)
53 | rostest.rosrun(PKG_NAME, TEST_NAME, TestBlockLaserClippingPlugin)
54 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/debug.bat:
--------------------------------------------------------------------------------
1 | @echo off
2 | SETLOCAL EnableDelayedExpansion
3 |
4 | SET "DESIRED_MASTER_URI=%GAZEBO_MASTER_URI%"
5 | SET "DESIRED_MODEL_DATABASE_URI=%GAZEBO_MODEL_DATABASE_URI%"
6 |
7 | SET "FINAL=%*"
8 |
9 | call :FIND_IN_WORKSPACES gazebo_ros_paths_plugin.dll
10 | SET "FINAL=%FINAL% -g %FIND_IN_WORKSPACES_OUTPUT%"
11 |
12 | call :FIND_IN_WORKSPACES gazebo_ros_api_plugin.dll
13 | SET "FINAL=%FINAL% -g %FIND_IN_WORKSPACES_OUTPUT%"
14 |
15 | SET GAZEBO_SETUP=
16 | FOR /F "tokens=* USEBACKQ" %%F IN (`pkg-config --variable=prefix gazebo`) DO (
17 | SET "GAZEBO_SETUP=%%F/share/gazebo/setup.bat"
18 | )
19 |
20 | SET REMAPPINGS_OUTPUT=
21 | SET OPTIONS_OUTPUT=
22 | call :RELOCATE_REMAPPINGS %FINAL%
23 |
24 | ENDLOCAL & SET "GAZEBO_OPTIONS=%OPTIONS_OUTPUT%%REMAPPINGS_OUTPUT%" & SET "GAZEBO_SETUP=%GAZEBO_SETUP%" & SET "DESIRED_MASTER_URI=%DESIRED_MASTER_URI%" & SET "DESIRED_MODEL_DATABASE_URI=%DESIRED_MODEL_DATABASE_URI%"
25 |
26 | CALL %GAZEBO_SETUP%
27 | SET "GAZEBO_MASTER_URI=%DESIRED_MASTER_URI%"
28 | SET "GAZEBO_MODEL_DATABASE_URI=%DESIRED_MODEL_DATABASE_URI%"
29 | gzserver %GAZEBO_OPTIONS%
30 |
31 | GOTO :EOF
32 |
33 | :RELOCATE_REMAPPINGS
34 | FOR /F "tokens=1*" %%A IN ("%*") DO (
35 | SET _REMAPPING=0
36 | SET _TEMP_VAR=%%A
37 | FOR %%A IN (!_TEMP_VAR!) DO (
38 | IF NOT "%%A"=="!_TEMP_VAR!" SET _REMAPPING=1
39 | )
40 | IF !_REMAPPING!==1 (
41 | SET "REMAPPINGS_OUTPUT=!REMAPPINGS_OUTPUT! !_TEMP_VAR!"
42 | ) ELSE (
43 | SET "OPTIONS_OUTPUT=!OPTIONS_OUTPUT! !_TEMP_VAR!"
44 | )
45 | IF NOT "%%B"=="" call :RELOCATE_REMAPPINGS %%B
46 | )
47 | EXIT /B
48 |
49 | :FIND_IN_WORKSPACES
50 | FOR /F "tokens=* USEBACKQ" %%F IN (`python -c "from catkin.find_in_workspaces import find_in_workspaces as catkin_find; print(catkin_find(path='%*')[0])"`) DO (
51 | SET "FIND_IN_WORKSPACES_OUTPUT="%%F""
52 | )
53 | EXIT /B
54 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/gzclient.bat:
--------------------------------------------------------------------------------
1 | @echo off
2 | SETLOCAL EnableDelayedExpansion
3 |
4 | SET "DESIRED_MASTER_URI=%GAZEBO_MASTER_URI%"
5 | SET "DESIRED_MODEL_DATABASE_URI=%GAZEBO_MODEL_DATABASE_URI%"
6 |
7 | SET "FINAL=%*"
8 |
9 | call :FIND_IN_WORKSPACES gazebo_ros_paths_plugin.dll
10 | SET "FINAL=%FINAL% -g %FIND_IN_WORKSPACES_OUTPUT%"
11 |
12 | call :FIND_IN_WORKSPACES gazebo_ros_api_plugin.dll
13 | SET "FINAL=%FINAL% -g %FIND_IN_WORKSPACES_OUTPUT%"
14 |
15 | SET GAZEBO_SETUP=
16 | FOR /F "tokens=* USEBACKQ" %%F IN (`pkg-config --variable=prefix gazebo`) DO (
17 | SET "GAZEBO_SETUP=%%F/share/gazebo/setup.bat"
18 | )
19 |
20 | SET REMAPPINGS_OUTPUT=
21 | SET OPTIONS_OUTPUT=
22 | call :RELOCATE_REMAPPINGS %FINAL%
23 |
24 | ENDLOCAL & SET "GAZEBO_OPTIONS=%OPTIONS_OUTPUT%%REMAPPINGS_OUTPUT%" & SET "GAZEBO_SETUP=%GAZEBO_SETUP%" & SET "DESIRED_MASTER_URI=%DESIRED_MASTER_URI%" & SET "DESIRED_MODEL_DATABASE_URI=%DESIRED_MODEL_DATABASE_URI%"
25 |
26 | CALL %GAZEBO_SETUP%
27 | SET "GAZEBO_MASTER_URI=%DESIRED_MASTER_URI%"
28 | SET "GAZEBO_MODEL_DATABASE_URI=%DESIRED_MODEL_DATABASE_URI%"
29 | gzclient %GAZEBO_OPTIONS%
30 |
31 | GOTO :EOF
32 |
33 | :RELOCATE_REMAPPINGS
34 | FOR /F "tokens=1*" %%A IN ("%*") DO (
35 | SET _REMAPPING=0
36 | SET _TEMP_VAR=%%A
37 | FOR %%A IN (!_TEMP_VAR!) DO (
38 | IF NOT "%%A"=="!_TEMP_VAR!" SET _REMAPPING=1
39 | )
40 | IF !_REMAPPING!==1 (
41 | SET "REMAPPINGS_OUTPUT=!REMAPPINGS_OUTPUT! !_TEMP_VAR!"
42 | ) ELSE (
43 | SET "OPTIONS_OUTPUT=!OPTIONS_OUTPUT! !_TEMP_VAR!"
44 | )
45 | IF NOT "%%B"=="" call :RELOCATE_REMAPPINGS %%B
46 | )
47 | EXIT /B
48 |
49 | :FIND_IN_WORKSPACES
50 | FOR /F "tokens=* USEBACKQ" %%F IN (`python -c "from catkin.find_in_workspaces import find_in_workspaces as catkin_find; print(catkin_find(path='%*')[0])"`) DO (
51 | SET "FIND_IN_WORKSPACES_OUTPUT="%%F""
52 | )
53 | EXIT /B
54 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/gzserver.bat:
--------------------------------------------------------------------------------
1 | @echo off
2 | SETLOCAL EnableDelayedExpansion
3 |
4 | SET "DESIRED_MASTER_URI=%GAZEBO_MASTER_URI%"
5 | SET "DESIRED_MODEL_DATABASE_URI=%GAZEBO_MODEL_DATABASE_URI%"
6 |
7 | SET "FINAL=%*"
8 |
9 | call :FIND_IN_WORKSPACES gazebo_ros_paths_plugin.dll
10 | SET "FINAL=%FINAL% -s %FIND_IN_WORKSPACES_OUTPUT%"
11 |
12 | call :FIND_IN_WORKSPACES gazebo_ros_api_plugin.dll
13 | SET "FINAL=%FINAL% -s %FIND_IN_WORKSPACES_OUTPUT%"
14 |
15 | SET GAZEBO_SETUP=
16 | FOR /F "tokens=* USEBACKQ" %%F IN (`pkg-config --variable=prefix gazebo`) DO (
17 | SET "GAZEBO_SETUP=%%F/share/gazebo/setup.bat"
18 | )
19 |
20 | SET REMAPPINGS_OUTPUT=
21 | SET OPTIONS_OUTPUT=
22 | call :RELOCATE_REMAPPINGS %FINAL%
23 |
24 | ENDLOCAL & SET "GAZEBO_OPTIONS=%OPTIONS_OUTPUT%%REMAPPINGS_OUTPUT%" & SET "GAZEBO_SETUP=%GAZEBO_SETUP%" & SET "DESIRED_MASTER_URI=%DESIRED_MASTER_URI%" & SET "DESIRED_MODEL_DATABASE_URI=%DESIRED_MODEL_DATABASE_URI%"
25 |
26 | CALL %GAZEBO_SETUP%
27 | SET "GAZEBO_MASTER_URI=%DESIRED_MASTER_URI%"
28 | SET "GAZEBO_MODEL_DATABASE_URI=%DESIRED_MODEL_DATABASE_URI%"
29 | gzserver %GAZEBO_OPTIONS%
30 |
31 | GOTO :EOF
32 |
33 | :RELOCATE_REMAPPINGS
34 | FOR /F "tokens=1*" %%A IN ("%*") DO (
35 | SET _REMAPPING=0
36 | SET _TEMP_VAR=%%A
37 | FOR %%A IN (!_TEMP_VAR!) DO (
38 | IF NOT "%%A"=="!_TEMP_VAR!" SET _REMAPPING=1
39 | )
40 | IF !_REMAPPING!==1 (
41 | SET "REMAPPINGS_OUTPUT=!REMAPPINGS_OUTPUT! !_TEMP_VAR!"
42 | ) ELSE (
43 | SET "OPTIONS_OUTPUT=!OPTIONS_OUTPUT! !_TEMP_VAR!"
44 | )
45 | IF NOT "%%B"=="" call :RELOCATE_REMAPPINGS %%B
46 | )
47 | EXIT /B
48 |
49 | :FIND_IN_WORKSPACES
50 | FOR /F "tokens=* USEBACKQ" %%F IN (`python -c "from catkin.find_in_workspaces import find_in_workspaces as catkin_find; print(catkin_find(path='%*')[0])"`) DO (
51 | SET "FIND_IN_WORKSPACES_OUTPUT="%%F""
52 | )
53 | EXIT /B
54 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_camera.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2012 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 | /*
18 | * Desc: A dynamic controller plugin that publishes ROS image_raw
19 | * camera_info topic for generic camera sensor.
20 | */
21 |
22 | #ifndef GAZEBO_ROS_CAMERA_HH
23 | #define GAZEBO_ROS_CAMERA_HH
24 |
25 | #include
26 |
27 | // library for processing camera data for gazebo / ros conversions
28 | #include
29 |
30 | #include
31 |
32 | namespace gazebo
33 | {
34 | class GazeboRosCamera : public CameraPlugin, GazeboRosCameraUtils
35 | {
36 | /// \brief Constructor
37 | /// \param parent The parent entity, must be a Model or a Sensor
38 | public: GazeboRosCamera();
39 |
40 | /// \brief Destructor
41 | public: ~GazeboRosCamera();
42 |
43 | /// \brief Load the plugin
44 | /// \param take in SDF root element
45 | public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
46 |
47 | /// \brief Update the controller
48 | protected: virtual void OnNewFrame(const unsigned char *_image,
49 | unsigned int _width, unsigned int _height,
50 | unsigned int _depth, const std::string &_format);
51 | };
52 | }
53 | #endif
54 |
55 |
--------------------------------------------------------------------------------
/gazebo_ros/scripts/gazebo:
--------------------------------------------------------------------------------
1 | #!/bin/sh
2 | [ -L ${0} ] && SCRIPT_DIR=$(readlink ${0}) || SCRIPT_DIR=${0}
3 | SCRIPT_DIR=$(dirname ${SCRIPT_DIR})
4 |
5 | . ${SCRIPT_DIR}/libcommon.sh
6 |
7 | final="$@"
8 |
9 | EXT=so
10 | if [ $(uname) = "Darwin" ]; then
11 | EXT=dylib
12 | fi
13 |
14 | # add ros path plugin if it does not already exist in the passed in arguments
15 | if [ `expr "$final" : ".*libgazebo_ros_paths_plugin\.$EXT.*"` -eq 0 ]
16 | then
17 | final="$final -s `catkin_find --first-only libgazebo_ros_paths_plugin.$EXT`"
18 | fi
19 |
20 | # add ros api plugin if it does not already exist in the passed in arguments
21 | if [ `expr "$final" : ".*libgazebo_ros_api_plugin\.$EXT.*"` -eq 0 ]
22 | then
23 | final="$final -s `catkin_find --first-only libgazebo_ros_api_plugin.$EXT`"
24 | fi
25 |
26 | client_final="-g `catkin_find --first-only libgazebo_ros_paths_plugin.$EXT`"
27 |
28 | setup_path=$(pkg-config --variable=prefix gazebo)/share/gazebo/
29 |
30 | # source setup.sh, but keep local modifications to GAZEBO_MASTER_URI and GAZEBO_MODEL_DATABASE_URI
31 | desired_master_uri="$GAZEBO_MASTER_URI"
32 | desired_model_database_uri="$GAZEBO_MODEL_DATABASE_URI"
33 | . $setup_path/setup.sh
34 | if [ "$desired_master_uri" = "" ]; then
35 | desired_master_uri="$GAZEBO_MASTER_URI"
36 | fi
37 | if [ "$desired_model_database_uri" = "" ]; then
38 | desired_model_database_uri="$GAZEBO_MODEL_DATABASE_URI"
39 | fi
40 |
41 | final=$(relocate_remappings "${final}")
42 |
43 | # Combine the commands
44 | GAZEBO_MASTER_URI="$desired_master_uri" GAZEBO_MODEL_DATABASE_URI="$desired_model_database_uri" gzserver $final &
45 | gzserver_pid="$!"
46 | # Use kill -0 to check if the process is running
47 | if $(kill -0 $! 2> /dev/null); then
48 | GAZEBO_MASTER_URI="$desired_master_uri" GAZEBO_MODEL_DATABASE_URI="$desired_model_database_uri" gzclient $client_final
49 | fi
50 |
51 | # Kill the server if it is alive
52 | if $(kill -0 $! 2> /dev/null); then
53 | # -2 SIGINT valid for Linux and Mac
54 | kill -2 $!
55 | fi
56 |
--------------------------------------------------------------------------------
/gazebo_ros/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | gazebo_ros
4 | 2.9.3
5 |
6 | Provides ROS plugins that offer message and service publishers for interfacing with Gazebo through ROS.
7 | Formally simulator_gazebo/gazebo
8 |
9 |
10 | Alejandro Hernández Cordero
11 | Jose Luis Rivero
12 |
13 | Apache 2.0
14 |
15 | http://gazebosim.org/tutorials?cat=connect_ros
16 | https://github.com/ros-simulation/gazebo_ros_pkgs/issues
17 | https://github.com/ros-simulation/gazebo_ros_pkgs
18 |
19 | John Hsu
20 | Nate Koenig
21 | Dave Coleman
22 |
23 | catkin
24 |
25 | cmake_modules
26 | gazebo_dev
27 |
31 | gazebo_dev
32 | gazebo_msgs
33 | roslib
34 | roscpp
35 | tf
36 | std_srvs
37 | rosgraph_msgs
38 | dynamic_reconfigure
39 | std_msgs
40 | geometry_msgs
41 | tinyxml
42 | python-argparse
43 |
44 |
45 | This package has been deprecated as of January 2025 with Gazebo classic 11 reaching
46 | end-of-life. Users are highly encouraged to migrate to the new Gazebo
47 | using our migration guides (https://gazebosim.org/docs/latest/gazebo_classic_migration)
48 |
49 |
50 |
51 |
--------------------------------------------------------------------------------
/gazebo_plugins/test2/CMakeLists_tests_pkg.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 | #uncomment if you have defined messages
20 | #rosbuild_genmsg()
21 | #uncomment if you have defined services
22 | #rosbuild_gensrv()
23 |
24 | rosbuild_add_boost_directories()
25 |
26 | rosbuild_add_executable(spawn_box test/spawn_model/spawn_box.cpp)
27 | rosbuild_add_gtest_build_flags(spawn_box)
28 | rosbuild_add_rostest_labeled(gazebo test/spawn_model/spawn_box.launch)
29 |
30 | rosbuild_add_executable(check_model test/spawn_model/check_model.cpp)
31 | rosbuild_add_gtest_build_flags(check_model)
32 | rosbuild_add_rostest_labeled(gazebo test/spawn_model/spawn_box_file.launch)
33 | rosbuild_add_rostest_labeled(gazebo test/spawn_model/spawn_box_param.launch)
34 |
35 | rosbuild_add_executable(contact_tolerance test/contact_tolerance/contact_tolerance.cpp)
36 | rosbuild_add_gtest_build_flags(contact_tolerance)
37 | rosbuild_add_rostest_labeled(gazebo test/contact_tolerance/contact_tolerance.launch)
38 |
39 | #common commands for building c++ executables and libraries
40 | #rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
41 | #target_link_libraries(${PROJECT_NAME} another_library)
42 | #rosbuild_link_boost(${PROJECT_NAME} thread)
43 | #rosbuild_add_executable(example examples/example.cpp)
44 | #target_link_libraries(example ${PROJECT_NAME})
45 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/MultiCameraPlugin.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2012 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 | #ifndef _GAZEBO_MULTI_CAMERA_PLUGIN_HH_
18 | #define _GAZEBO_MULTI_CAMERA_PLUGIN_HH_
19 |
20 | #include
21 | #include
22 |
23 | #include
24 | #include
25 | #include
26 | #include
27 |
28 | namespace gazebo
29 | {
30 | class MultiCameraPlugin : public SensorPlugin
31 | {
32 | public: MultiCameraPlugin();
33 |
34 | /// \brief Destructor
35 | public: virtual ~MultiCameraPlugin();
36 |
37 | public: virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
38 |
39 | public: virtual void OnNewFrameLeft(const unsigned char *_image,
40 | unsigned int _width, unsigned int _height,
41 | unsigned int _depth, const std::string &_format);
42 | public: virtual void OnNewFrameRight(const unsigned char *_image,
43 | unsigned int _width, unsigned int _height,
44 | unsigned int _depth, const std::string &_format);
45 |
46 | protected: sensors::MultiCameraSensorPtr parentSensor;
47 |
48 | protected: std::vector width, height, depth;
49 | protected: std::vector format;
50 |
51 | protected: std::vector camera;
52 |
53 | private: std::vector newFrameConnection;
54 | };
55 | }
56 | #endif
57 |
--------------------------------------------------------------------------------
/gazebo_ros/launch/elevator_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
--------------------------------------------------------------------------------
/gazebo_plugins/scripts/gazebo_model:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | #
3 | # testing, do not use
4 | #
5 | # Provides quick access to the services exposed by gazebo_ros_factory plugin
6 |
7 | import roslib, time
8 | roslib.load_manifest('gazebo_plugins')
9 |
10 | import rospy, sys
11 | import string
12 |
13 | from gazebo_plugins import gazebo_plugins_interface
14 | from gazebo_plugins.msg import GazeboModel
15 | from geometry_msgs.msg import Pose, Point, Quaternion
16 |
17 | def usage():
18 | print('''Commands:
19 | load [param|file] [urdf|gazebo] - Load model
20 | delete - Deletes the model named
21 | ''')
22 | sys.exit(1)
23 |
24 | if __name__ == "__main__":
25 | if len(sys.argv) < 13:
26 | usage()
27 |
28 | if sys.argv[1] == 'load':
29 | if sys.argv[2] == 'param':
30 | print("loading from parameter")
31 | elif sys.argv[2] == 'file':
32 | print("loading from file")
33 | else:
34 | print("invalid syntax, first argument has to be either param or file")
35 | usage()
36 |
37 | if sys.argv[3] == 'urdf':
38 | print("loading urdf")
39 | elif sys.argv[3] == 'gazebo':
40 | print("loading gazebo model")
41 | else:
42 | print("invalid syntax, xml type has to be either urdf or gazebo")
43 | usage()
44 |
45 | param_name = sys.argv[4]
46 | model_name = sys.argv[5]
47 | lx = float(sys.argv[6])
48 | ly = float(sys.argv[7])
49 | lz = float(sys.argv[8])
50 |
51 | #FIXME: rotation ignored for now
52 | ax = float(sys.argv[9])
53 | ay = float(sys.argv[10])
54 | az = float(sys.argv[11])
55 |
56 | namespace = sys.argv[12]
57 |
58 | model_msg = GazeboModel(model_name,param_name,GazeboModel.URDF_PARAM_NAME,namespace,Pose(Point(lx,ly,lz),Quaternion()))
59 | success = gazebo_plugins_interface.load_model(model_msg)
60 | print("spawning success", success)
61 |
62 | elif sys.argv[1] == 'delete':
63 | print("not implemented yet")
64 |
65 | else:
66 | print("unknown command: ", sys.argv[1])
67 | usage()
68 |
--------------------------------------------------------------------------------
/gazebo_plugins/src/camera_synchronizer.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2009-2010, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | #include
36 |
37 | int main(int argc, char **argv)
38 | {
39 | ros::init(argc, argv, "camera_synchronizer");
40 |
41 | VisionReconfigure vr;
42 |
43 | double spin_frequency = 100.0;
44 | ROS_INFO_NAMED("camera_synchronizer", "Starting to spin camera_synchronizer at %f Hz...",spin_frequency);
45 | vr.spin(spin_frequency);
46 |
47 | return 0;
48 | }
49 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_hand_of_god.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (C) 2012-2014 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 | /*
18 | * Desc: 3D position interface.
19 | * Author: Sachin Chitta and John Hsu
20 | * Date: 10 June 2008
21 | */
22 |
23 | #ifndef GAZEBO_ROS_TEMPLATE_HH
24 | #define GAZEBO_ROS_TEMPLATE_HH
25 |
26 | #include
27 |
28 | #include
29 | #include
30 | #include
31 | #include
32 | #include
33 |
34 | #include
35 | #include
36 |
37 | namespace gazebo
38 | {
39 |
40 | class GazeboRosHandOfGod : public ModelPlugin
41 | {
42 | /// \brief Constructor
43 | public: GazeboRosHandOfGod();
44 |
45 | /// \brief Destructor
46 | public: virtual ~GazeboRosHandOfGod();
47 |
48 | /// \brief Load the controller
49 | public: void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
50 |
51 | /// \brief Update the controller
52 | protected: virtual void GazeboUpdate();
53 |
54 | /// Pointer to the update event connection
55 | private: event::ConnectionPtr update_connection_;
56 | boost::shared_ptr tf_buffer_;
57 | boost::shared_ptr tf_listener_;
58 | boost::shared_ptr tf_broadcaster_;
59 | physics::ModelPtr model_;
60 | physics::LinkPtr floating_link_;
61 | std::string link_name_;
62 | std::string robot_namespace_;
63 | std::string frame_id_;
64 | double kl_, ka_;
65 | double cl_, ca_;
66 | };
67 |
68 | }
69 |
70 | #endif
71 |
72 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 | 0 0 0 0 0 0
37 |
38 |
39 |
40 |
41 | 1
42 | 2.0944
43 | -2.0944
44 | 683
45 |
46 |
47 |
48 | 0.08
49 | 5
50 | 0.01
51 |
52 |
53 |
54 |
55 |
56 | ${name}/scan
57 | ${name}
58 |
59 |
62 |
63 | 1
64 | 30
65 | true
66 |
67 |
68 |
69 |
70 |
71 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_elevator.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2015 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 |
18 | #ifndef _GAZEBO_ROS_PLUGINS_ELEVATOR_PLUGIN_H_
19 | #define _GAZEBO_ROS_PLUGINS_ELEVATOR_PLUGIN_H_
20 |
21 | #include
22 |
23 | // Gazebo
24 | #include
25 |
26 | // ROS
27 | #include
28 | #include
29 | #include
30 | #include
31 |
32 | namespace gazebo
33 | {
34 | /// \brief ROS implementation of the Elevator plugin
35 | class GazeboRosElevator : public ElevatorPlugin
36 | {
37 | /// \brief Constructor
38 | public: GazeboRosElevator();
39 |
40 | /// \brief Destructor
41 | public: virtual ~GazeboRosElevator();
42 |
43 | /// \brief Load the plugin.
44 | /// \param[in] _model Pointer to the Model
45 | /// \param[in] _sdf Pointer to the SDF element of the plugin.
46 | public: void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
47 |
48 | /// \brief Receives messages on the elevator's topic.
49 | /// \param[in] _msg The string message that contains a command.
50 | public: void OnElevator(const std_msgs::String::ConstPtr &_msg);
51 |
52 | /// \brief Queu to handle callbacks.
53 | private: void QueueThread();
54 |
55 | /// \brief for setting ROS name space
56 | private: std::string robotNamespace_;
57 |
58 | /// \brief ros node handle
59 | private: ros::NodeHandle *rosnode_;
60 |
61 | /// \brief Subscribes to a topic that controls the elevator.
62 | private: ros::Subscriber elevatorSub_;
63 |
64 | /// \brief Custom Callback Queue
65 | private: ros::CallbackQueue queue_;
66 |
67 | // \brief Custom Callback Queue thread
68 | private: boost::thread callbackQueueThread_;
69 | };
70 | }
71 | #endif
72 |
--------------------------------------------------------------------------------
/gazebo_plugins/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | gazebo_plugins
4 | 2.9.3
5 |
6 | Robot-independent Gazebo plugins for sensors, motors and dynamic reconfigurable components.
7 |
8 |
9 | Alejandro Hernández Cordero
10 | Jose Luis Rivero
11 |
12 | BSD, Apache 2.0
13 |
14 | http://gazebosim.org/tutorials?cat=connect_ros
15 | https://github.com/ros-simulation/gazebo_ros_pkgs/issues
16 | https://github.com/ros-simulation/gazebo_ros_pkgs
17 |
18 | John Hsu
19 |
20 | catkin
21 |
22 | gazebo_dev
23 |
27 | gazebo_dev
28 |
29 | gazebo_ros
30 | gazebo_msgs
31 | geometry_msgs
32 | sensor_msgs
33 | trajectory_msgs
34 | visualization_msgs
35 | std_srvs
36 | roscpp
37 | rospy
38 | nodelet
39 | angles
40 | nav_msgs
41 | urdf
42 | tf
43 | tf2_ros
44 | dynamic_reconfigure
45 | rosgraph_msgs
46 | image_transport
47 | rosconsole
48 | message_generation
49 | message_runtime
50 | cv_bridge
51 | polled_camera
52 | diagnostic_updater
53 | camera_info_manager
54 | std_msgs
55 |
56 | rostest
57 |
58 |
59 |
60 |
61 | This package has been deprecated as of January 2025 with Gazebo classic 11 reaching
62 | end-of-life. Users are highly encouraged to migrate to the new Gazebo
63 | using our migration guides (https://gazebosim.org/docs/latest/gazebo_classic_migration)
64 |
65 |
66 |
67 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_multicamera.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2012 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 |
18 | #ifndef GAZEBO_ROS_MULTICAMERA_HH
19 | #define GAZEBO_ROS_MULTICAMERA_HH
20 |
21 | #include
22 | #include
23 |
24 | // library for processing camera data for gazebo / ros conversions
25 | #include
26 | #include
27 |
28 | namespace gazebo
29 | {
30 | class GazeboRosMultiCamera : public MultiCameraPlugin
31 | {
32 | /// \brief Constructor
33 | /// \param parent The parent entity, must be a Model or a Sensor
34 | public: GazeboRosMultiCamera();
35 |
36 | /// \brief Destructor
37 | public: ~GazeboRosMultiCamera();
38 |
39 | /// \brief Load the plugin
40 | /// \param take in SDF root element
41 | public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
42 |
43 | std::vector utils;
44 |
45 | protected: void OnNewFrame(const unsigned char *_image,
46 | GazeboRosCameraUtils* util);
47 | /// \brief Update the controller
48 | /// FIXME: switch to function vectors
49 | protected: virtual void OnNewFrameLeft(const unsigned char *_image,
50 | unsigned int _width, unsigned int _height,
51 | unsigned int _depth, const std::string &_format);
52 | protected: virtual void OnNewFrameRight(const unsigned char *_image,
53 | unsigned int _width, unsigned int _height,
54 | unsigned int _depth, const std::string &_format);
55 |
56 | /// Bookkeeping flags that will be passed into the underlying
57 | /// GazeboRosCameraUtils objects to let them share state about the parent
58 | /// sensor.
59 | private: boost::shared_ptr image_connect_count_;
60 | private: boost::shared_ptr image_connect_count_lock_;
61 | private: boost::shared_ptr was_active_;
62 | };
63 | }
64 | #endif
65 |
66 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro:
--------------------------------------------------------------------------------
1 |
2 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_multicamera.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2017 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 |
18 | #ifndef GAZEBO_ROS_TRIGGERED_MULTICAMERA_HH
19 | #define GAZEBO_ROS_TRIGGERED_MULTICAMERA_HH
20 |
21 | #include
22 | #include
23 |
24 | // library for processing camera data for gazebo / ros conversions
25 | #include
26 | #include
27 |
28 | namespace gazebo
29 | {
30 | class GazeboRosTriggeredMultiCamera : public MultiCameraPlugin
31 | {
32 | /// \brief Constructor
33 | /// \param parent The parent entity, must be a Model or a Sensor
34 | public: GazeboRosTriggeredMultiCamera();
35 |
36 | /// \brief Destructor
37 | public: ~GazeboRosTriggeredMultiCamera();
38 |
39 | /// \brief Load the plugin
40 | /// \param take in SDF root element
41 | public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
42 |
43 | std::vector triggered_cameras;
44 |
45 | /// \brief Update the controller
46 | /// FIXME: switch to function vectors
47 | protected: virtual void OnNewFrameLeft(const unsigned char *_image,
48 | unsigned int _width, unsigned int _height,
49 | unsigned int _depth, const std::string &_format);
50 | protected: virtual void OnNewFrameRight(const unsigned char *_image,
51 | unsigned int _width, unsigned int _height,
52 | unsigned int _depth, const std::string &_format);
53 |
54 | /// Bookkeeping flags that will be passed into the underlying
55 | /// GazeboRosCameraUtils objects to let them share state about the parent
56 | /// sensor.
57 | private: boost::shared_ptr image_connect_count_;
58 | private: boost::shared_ptr image_connect_count_lock_;
59 | private: boost::shared_ptr was_active_;
60 |
61 | protected: event::ConnectionPtr preRenderConnection_;
62 | protected: void SetCameraEnabled(const bool _enabled);
63 | protected: void PreRender();
64 | };
65 | }
66 | #endif
67 |
68 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_triggered_camera.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2017 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 |
18 | #ifndef GAZEBO_ROS_TRIGGERED_CAMERA_HH
19 | #define GAZEBO_ROS_TRIGGERED_CAMERA_HH
20 |
21 | #include
22 | #include
23 |
24 | // library for processing camera data for gazebo / ros conversions
25 | #include
26 |
27 | #include
28 |
29 | namespace gazebo
30 | {
31 | class GazeboRosTriggeredMultiCamera;
32 | class GazeboRosTriggeredCamera : public CameraPlugin, GazeboRosCameraUtils
33 | {
34 | /// \brief Constructor
35 | /// \param parent The parent entity, must be a Model or a Sensor
36 | public: GazeboRosTriggeredCamera();
37 |
38 | /// \brief Destructor
39 | public: ~GazeboRosTriggeredCamera();
40 |
41 | /// \brief Load the plugin
42 | /// \param take in SDF root element
43 | public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
44 |
45 | /// \brief Load the plugin.
46 | /// \param[in] _parent Take in SDF root element.
47 | /// \param[in] _sdf SDF values.
48 | /// \param[in] _camera_name_suffix Suffix of the camera name.
49 | /// \param[in] _hack_baseline Multiple camera baseline.
50 | public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf,
51 | const std::string &_camera_name_suffix,
52 | double _hack_baseline);
53 |
54 | /// \brief Update the controller
55 | protected: virtual void OnNewFrame(const unsigned char *_image,
56 | unsigned int _width, unsigned int _height,
57 | unsigned int _depth, const std::string &_format);
58 |
59 | protected: virtual void TriggerCamera();
60 |
61 | protected: virtual bool CanTriggerCamera();
62 |
63 | protected: event::ConnectionPtr preRenderConnection_;
64 |
65 | public: void SetCameraEnabled(const bool _enabled);
66 |
67 | protected: void PreRender();
68 |
69 | protected: int triggered = 0;
70 |
71 | protected: std::mutex mutex;
72 |
73 | friend class GazeboRosTriggeredMultiCamera;
74 | };
75 | }
76 | #endif
77 |
78 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/laser/hokuyo_gpu.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 | 0 0 0 0 0 0
37 | 1
38 | 30
39 | true
40 |
41 |
42 |
43 |
44 | 1
45 | 2.0944
46 | -2.0944
47 |
48 |
49 | 683
50 |
51 |
52 |
53 | 0.10
54 | 140.0
55 | 0.01
56 |
57 |
58 | gaussian
59 |
63 | 0.0
64 | 0.01
65 |
66 |
67 |
68 |
69 | ${name}/scan
70 | ${name}
71 |
72 |
73 |
74 |
75 |
76 |
77 |
--------------------------------------------------------------------------------
/gazebo_ros/src/gazebo_ros/gazebo_interface.py:
--------------------------------------------------------------------------------
1 | #! /usr/bin/env python
2 | # Wrappers around the services provided by rosified gazebo
3 |
4 | import sys
5 | import rospy
6 | import os
7 | import time
8 |
9 | from gazebo_msgs.msg import *
10 | from gazebo_msgs.srv import *
11 | from geometry_msgs.msg import Point, Pose, Quaternion, Twist, Wrench
12 |
13 |
14 | def spawn_sdf_model_client(model_name, model_xml, robot_namespace, initial_pose, reference_frame, gazebo_namespace):
15 | rospy.loginfo("Waiting for service %s/spawn_sdf_model"%gazebo_namespace)
16 | rospy.wait_for_service(gazebo_namespace+'/spawn_sdf_model')
17 | try:
18 | spawn_sdf_model = rospy.ServiceProxy(gazebo_namespace+'/spawn_sdf_model', SpawnModel)
19 | rospy.loginfo("Calling service %s/spawn_sdf_model"%gazebo_namespace)
20 | resp = spawn_sdf_model(model_name, model_xml, robot_namespace, initial_pose, reference_frame)
21 | rospy.loginfo("Spawn status: %s"%resp.status_message)
22 | return resp.success
23 | except rospy.ServiceException as e:
24 | print("Service call failed: %s" % e)
25 |
26 | def spawn_urdf_model_client(model_name, model_xml, robot_namespace, initial_pose, reference_frame, gazebo_namespace):
27 | rospy.loginfo("Waiting for service %s/spawn_urdf_model"%gazebo_namespace)
28 | rospy.wait_for_service(gazebo_namespace+'/spawn_urdf_model')
29 | try:
30 | spawn_urdf_model = rospy.ServiceProxy(gazebo_namespace+'/spawn_urdf_model', SpawnModel)
31 | rospy.loginfo("Calling service %s/spawn_urdf_model"%gazebo_namespace)
32 | resp = spawn_urdf_model(model_name, model_xml, robot_namespace, initial_pose, reference_frame)
33 | rospy.loginfo("Spawn status: %s"%resp.status_message)
34 | return resp.success
35 | except rospy.ServiceException as e:
36 | print("Service call failed: %s" % e)
37 |
38 | def set_model_configuration_client(model_name, model_param_name, joint_names, joint_positions, gazebo_namespace):
39 | rospy.loginfo("Waiting for service %s/set_model_configuration"%gazebo_namespace)
40 | rospy.wait_for_service(gazebo_namespace+'/set_model_configuration')
41 | rospy.loginfo("temporary hack to **fix** the -J joint position option (issue #93), sleeping for 1 second to avoid race condition.");
42 | time.sleep(1)
43 | try:
44 | set_model_configuration = rospy.ServiceProxy(gazebo_namespace+'/set_model_configuration', SetModelConfiguration)
45 | rospy.loginfo("Calling service %s/set_model_configuration"%gazebo_namespace)
46 | resp = set_model_configuration(model_name, model_param_name, joint_names, joint_positions)
47 | rospy.loginfo("Set model configuration status: %s"%resp.status_message)
48 |
49 | return resp.success
50 | except rospy.ServiceException as e:
51 | print("Service call failed: %s" % e)
52 |
53 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/camera/camera.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
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 |
38 |
39 |
40 |
41 | 30.0
42 |
43 | 1.3962634
44 |
45 | 800
46 | 800
47 | R8G8B8
48 |
49 |
50 | 0.02
51 | 300
52 |
53 |
54 | gaussian
55 |
58 | 0.0
59 | 0.007
60 |
61 |
62 |
63 |
64 | true
65 | 0.0
66 | ${name}
67 | image_raw
68 | camera_info
69 | ${name}
70 | 0.07
71 | 0.0
72 | 0.0
73 | 0.0
74 | 0.0
75 | 0.0
76 |
77 |
78 |
79 |
80 |
81 |
82 |
--------------------------------------------------------------------------------
/gazebo_ros_control/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5.1)
2 | project(gazebo_ros_control)
3 |
4 | # Load catkin and all dependencies required for this package
5 | find_package(catkin REQUIRED COMPONENTS
6 | gazebo_dev
7 | roscpp
8 | std_msgs
9 | control_toolbox
10 | controller_manager
11 | hardware_interface
12 | transmission_interface
13 | pluginlib
14 | joint_limits_interface
15 | urdf
16 | angles
17 | )
18 |
19 | # Through transitive dependencies in the packages above, gazebo_ros_control
20 | # depends on Simbody. There is a bug in the Ubuntu Artful (17.10) version of
21 | # the Simbody package where it includes /usr/lib/libblas.so and
22 | # /usr/lib/liblapack.so in the CMake list of libraries even though neither of
23 | # those two paths exist (they both really live in /usr/lib/-linux-gnu).
24 | # We remove these two during build-time on artful below; this works because
25 | # they both will get resolved to the proper paths during runtime linking.
26 | find_program(LSB_RELEASE_EXEC lsb_release)
27 | if(NOT LSB_RELEASE_EXEC STREQUAL "LSB_RELEASE_EXEC-NOTFOUND")
28 | execute_process(COMMAND ${LSB_RELEASE_EXEC} -cs
29 | OUTPUT_VARIABLE OS_CODENAME
30 | OUTPUT_STRIP_TRAILING_WHITESPACE
31 | )
32 | if(OS_CODENAME STREQUAL "artful")
33 | list(FILTER catkin_LIBRARIES EXCLUDE REGEX "/usr/lib/libblas.so")
34 | list(FILTER catkin_LIBRARIES EXCLUDE REGEX "/usr/lib/liblapack.so")
35 | endif()
36 | endif()
37 |
38 | catkin_package(
39 | CATKIN_DEPENDS
40 | roscpp
41 | std_msgs
42 | controller_manager
43 | control_toolbox
44 | pluginlib
45 | hardware_interface
46 | transmission_interface
47 | joint_limits_interface
48 | urdf
49 | angles
50 | INCLUDE_DIRS include
51 | LIBRARIES ${PROJECT_NAME} default_robot_hw_sim
52 | )
53 |
54 | link_directories(
55 | ${catkin_LIBRARY_DIRS}
56 | )
57 |
58 | include_directories(include
59 | ${Boost_INCLUDE_DIR}
60 | ${catkin_INCLUDE_DIRS}
61 | )
62 |
63 | ## Restrict Windows header namespace usage
64 | if(WIN32)
65 | add_definitions(-DNOGDI)
66 | endif()
67 |
68 | ## Libraries
69 | add_library(${PROJECT_NAME} src/gazebo_ros_control_plugin.cpp)
70 | target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
71 |
72 | add_library(default_robot_hw_sim src/default_robot_hw_sim.cpp)
73 | target_link_libraries(default_robot_hw_sim ${catkin_LIBRARIES})
74 |
75 | ## Install
76 | install(TARGETS ${PROJECT_NAME} default_robot_hw_sim
77 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
78 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
79 | RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
80 | )
81 |
82 | install(DIRECTORY include/${PROJECT_NAME}/
83 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
84 | )
85 |
86 | install(FILES robot_hw_sim_plugins.xml
87 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
88 | )
89 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_harness.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (C) 2016 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 | #ifndef GAZEBO_ROS_HARNESS_H
18 | #define GAZEBO_ROS_HARNESS_H
19 |
20 | // Custom Callback Queue
21 | #include
22 | #include
23 |
24 | #include
25 | #include
26 | #include
27 |
28 | #include
29 |
30 | namespace gazebo
31 | {
32 | /// \brief See the Gazebo documentation about the HarnessPlugin. This ROS
33 | /// wrapper exposes two topics:
34 | ///
35 | /// 1. //harness/velocity
36 | /// - Message Type: std_msgs::Float32
37 | /// - Purpose: Set target winch velocity
38 | ///
39 | /// 2. //harness/detach
40 | /// - Message Type: std_msgs::Bool
41 | /// - Purpose: Detach the joint.
42 | class GazeboRosHarness : public HarnessPlugin
43 | {
44 | /// \brief Constructor
45 | public: GazeboRosHarness();
46 |
47 | /// \brief Destructor
48 | public: virtual ~GazeboRosHarness();
49 |
50 | /// \brief Load the plugin
51 | public: virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
52 |
53 | /// \brief Receive winch velocity control messages.
54 | /// \param[in] msg Float message that is the target winch velocity.
55 | private: virtual void OnVelocity(const std_msgs::Float32::ConstPtr &msg);
56 |
57 | /// \brief Receive detach messages
58 | /// \param[in] msg Boolean detach message. Detach joints if data is
59 | /// true.
60 | private: virtual void OnDetach(const std_msgs::Bool::ConstPtr &msg);
61 |
62 | /// \brief Custom callback queue thread
63 | private: void QueueThread();
64 |
65 | /// \brief pointer to ros node
66 | private: ros::NodeHandle *rosnode_;
67 |
68 | /// \brief Subscriber to velocity control messages.
69 | private: ros::Subscriber velocitySub_;
70 |
71 | /// \brief Subscriber to detach control messages.
72 | private: ros::Subscriber detachSub_;
73 |
74 | /// \brief for setting ROS name space
75 | private: std::string robotNamespace_;
76 | private: ros::CallbackQueue queue_;
77 | private: boost::thread callbackQueueThread_;
78 | };
79 | }
80 | #endif
81 |
--------------------------------------------------------------------------------
/gazebo_ros/launch/empty_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
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 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
49 |
50 |
51 |
52 |
54 |
55 |
56 |
57 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_bumper.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2012 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 |
18 | #ifndef GAZEBO_ROS_BUMPER_HH
19 | #define GAZEBO_ROS_BUMPER_HH
20 |
21 | #include
22 |
23 | #include
24 | #include
25 | #include
26 |
27 | #ifndef _WIN32
28 | #include
29 | #endif
30 |
31 | #include
32 | #include
33 |
34 | #include
35 |
36 | #include
37 | #include
38 |
39 | #include
40 | #include
41 | #include
42 | #include
43 | #include
44 | #include
45 | #include
46 | #include
47 | #include
48 | #include
49 |
50 | namespace gazebo
51 | {
52 | /// \brief A Bumper controller
53 | class GazeboRosBumper : public SensorPlugin
54 | {
55 | /// Constructor
56 | public: GazeboRosBumper();
57 |
58 | /// Destructor
59 | public: ~GazeboRosBumper();
60 |
61 | /// \brief Load the plugin
62 | /// \param take in SDF root element
63 | public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
64 |
65 | /// Update the controller
66 | private: void OnContact();
67 |
68 | /// \brief pointer to ros node
69 | private: ros::NodeHandle* rosnode_;
70 | private: ros::Publisher contact_pub_;
71 |
72 | private: sensors::ContactSensorPtr parentSensor;
73 |
74 | /// \brief set topic name of broadcast
75 | private: std::string bumper_topic_name_;
76 |
77 | private: std::string frame_name_;
78 |
79 | /// \brief broadcast some string for now.
80 | private: gazebo_msgs::ContactsState contact_state_msg_;
81 |
82 | /// \brief for setting ROS name space
83 | private: std::string robot_namespace_;
84 |
85 | private: ros::CallbackQueue contact_queue_;
86 | private: void ContactQueueThread();
87 | private: boost::thread callback_queue_thread_;
88 |
89 | // Pointer to the update event connection
90 | private: event::ConnectionPtr update_connection_;
91 | };
92 | }
93 |
94 | #endif
95 |
96 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/vision_reconfigure.h:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2009-2010, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | #ifndef VISION_RECONFIGURE_HH
36 | #define VISION_RECONFIGURE_HH
37 |
38 | #include
39 | #include
40 | #include
41 | #include
42 | #include
43 | #include
44 |
45 | #include
46 |
47 | class VisionReconfigure
48 | {
49 | public:
50 | VisionReconfigure();
51 |
52 | ~VisionReconfigure();
53 |
54 | void ReconfigureCallback(gazebo_plugins::CameraSynchronizerConfig &config, uint32_t level);
55 | void QueueThread();
56 | void spinOnce();
57 | void spin(double spin_frequency);
58 |
59 | private:
60 | ros::NodeHandle nh_;
61 | ros::Publisher pub_projector_;
62 | ros::Publisher pub_header_;
63 | dynamic_reconfigure::Server srv_;
64 | std_msgs::Int32 projector_msg_;
65 | ros::CallbackQueue queue_;
66 | boost::thread callback_queue_thread_;
67 |
68 | };
69 |
70 | #endif
71 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/camera/camera.h:
--------------------------------------------------------------------------------
1 | #ifndef GAZEBO_PLUGINS_TEST_CAMERA_CAMERA_H
2 | #define GAZEBO_PLUGINS_TEST_CAMERA_CAMERA_H
3 |
4 | #include
5 | #include
6 | #include
7 |
8 | class CameraTest : public testing::Test
9 | {
10 | protected:
11 | virtual void SetUp()
12 | {
13 | has_new_image_ = false;
14 | }
15 |
16 | ros::NodeHandle nh_;
17 | image_transport::Subscriber cam_sub_;
18 | bool has_new_image_;
19 | ros::Time image_stamp_;
20 | public:
21 | void subscribeTest();
22 |
23 | void imageCallback(const sensor_msgs::ImageConstPtr& msg)
24 | {
25 | image_stamp_ = msg->header.stamp;
26 | has_new_image_ = true;
27 | }
28 | };
29 |
30 | // Test if the camera image is published at all, and that the timestamp
31 | // is not too long in the past.
32 | void CameraTest::subscribeTest()
33 | {
34 | image_transport::ImageTransport it(nh_);
35 | cam_sub_ = it.subscribe("camera1/image_raw", 1,
36 | &CameraTest::imageCallback,
37 | dynamic_cast(this));
38 |
39 | #if 0
40 | // wait for gazebo to start publishing
41 | // TODO(lucasw) this isn't really necessary since this test
42 | // is purely passive
43 | bool wait_for_topic = true;
44 | while (wait_for_topic)
45 | {
46 | // @todo this fails without the additional 0.5 second sleep after the
47 | // publisher comes online, which means on a slower or more heavily
48 | // loaded system it may take longer than 0.5 seconds, and the test
49 | // would hang until the timeout is reached and fail.
50 | if (cam_sub_.getNumPublishers() > 0)
51 | wait_for_topic = false;
52 | ros::Duration(0.5).sleep();
53 | }
54 | #endif
55 |
56 | while (!has_new_image_)
57 | {
58 | ros::spinOnce();
59 | ros::Duration(0.1).sleep();
60 | }
61 |
62 | // This check depends on the update period being much longer
63 | // than the expected difference between now and the received image time
64 | // TODO(lucasw)
65 | // this likely isn't that robust - what if the testing system is really slow?
66 | double time_diff = (ros::Time::now() - image_stamp_).toSec();
67 | ROS_INFO_STREAM(time_diff);
68 | EXPECT_LT(time_diff, 1.0);
69 | cam_sub_.shutdown();
70 |
71 | // make sure nothing is subscribing to image_trigger topic
72 | // there is no easy API, so call getSystemState
73 | XmlRpc::XmlRpcValue args, result, payload;
74 | args[0] = ros::this_node::getName();
75 | EXPECT_TRUE(ros::master::execute("getSystemState", args, result, payload, true));
76 | // [publishers, subscribers, services]
77 | // subscribers in index 1 of payload
78 | for (int i = 0; i < payload[1].size(); ++i)
79 | {
80 | // [ [topic1, [topic1Subscriber1...topic1SubscriberN]] ... ]
81 | // topic name i is in index 0
82 | std::string topic = payload[1][i][0];
83 | EXPECT_EQ(topic.find("image_trigger"), std::string::npos);
84 | }
85 | }
86 |
87 | #endif
88 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/test_worlds/gazebo_ros_block_laser_clipping.world:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | 0 0 0.8 0.0 1.5707 0.0
6 | true
7 |
8 |
9 | 0.007 0 -0.033 0 0 0
10 |
11 |
12 | 0.07 0.065 0.065
13 |
14 |
15 |
16 |
17 |
18 |
19 | 0.07 0.065 0.065
20 |
21 |
22 |
23 |
24 | 5
25 | 0 0 0.0 0 0 0
26 |
27 | /
28 | test_block_laser_frame
29 | test_block_laser
30 | true
31 |
32 |
33 |
34 | 0.4
35 | 1.0
36 | 0.001
37 |
38 |
39 |
40 | 50
41 | 1
42 | -0.3
43 | 0.3
44 |
45 |
46 | 50
47 | 1
48 | -0.4
49 | 0.4
50 |
51 |
52 |
53 | gaussian
54 | 0.0
55 | 0.001
56 |
57 |
58 |
59 | 1
60 | True
61 |
62 | false
63 |
64 | 0.1
65 |
66 |
67 |
68 |
69 |
70 | true
71 | 0.0991 -0.002 0.0909 -0.254819 0.847737 -0.021658
72 |
73 |
74 |
75 |
76 | 1 0.1 0.1
77 |
78 |
79 |
80 |
81 |
82 |
83 | 1 0.1 0.1
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_wheel_slip.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright (C) 2017 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 | #ifndef GAZEBO_ROS_WHEEL_SLIP_H
18 | #define GAZEBO_ROS_WHEEL_SLIP_H
19 |
20 | // Custom Callback Queue
21 | #include
22 | #include
23 |
24 | #include
25 | #include
26 |
27 | // dynamic reconfigure stuff
28 | #include
29 | #include
30 |
31 | #include
32 |
33 | namespace gazebo
34 | {
35 | /// \brief See the Gazebo documentation about the WheelSlipPlugin. This ROS
36 | /// wrapper exposes two parameters via dynamic reconfigure:
37 | ///
38 | /// 1. slip_compliance_unitless_lateral
39 | /// - Type: double
40 | /// - Description: Unitless slip compliance (slip / friction) in the
41 | /// lateral direction. This value is applied to all wheels declared
42 | /// in the WheelSlipPlugin.
43 | ///
44 | /// 2. slip_compliance_unitless_longitudinal
45 | /// - Type: double
46 | /// - Description: Unitless slip compliance (slip / friction) in the
47 | /// longitudinal direction. This value is applied to all wheels declared
48 | /// in the WheelSlipPlugin.
49 | class GazeboRosWheelSlip : public WheelSlipPlugin
50 | {
51 | /// \brief Constructor
52 | public: GazeboRosWheelSlip();
53 |
54 | /// \brief Destructor
55 | public: virtual ~GazeboRosWheelSlip();
56 |
57 | /// \brief Load the plugin
58 | public: virtual void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf);
59 |
60 | /// \brief Custom callback queue thread
61 | private: void QueueThread();
62 |
63 | // Allow dynamic reconfiguration of wheel slip params
64 | private: void configCallback(
65 | gazebo_plugins::WheelSlipConfig &config,
66 | uint32_t level);
67 |
68 | /// \brief pointer to ros node
69 | private: ros::NodeHandle *rosnode_;
70 |
71 | /// \brief Dynamic reconfigure server.
72 | private: dynamic_reconfigure::Server
73 | *dyn_srv_;
74 |
75 | /// \brief for setting ROS name space
76 | private: std::string robotNamespace_;
77 | private: ros::CallbackQueue queue_;
78 | private: boost::thread callbackQueueThread_;
79 | };
80 | }
81 | #endif
82 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/pub_joint_trajectory_test.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 | #include
4 | #include
5 | #include
6 |
7 | int main(int argc, char** argv)
8 | {
9 |
10 | ros::init(argc, argv, "pub_joint_trajectory_test");
11 | ros::NodeHandle rosnode;
12 | ros::Publisher pub_ = rosnode.advertise("set_joint_trajectory",100);
13 | ros::ServiceClient srv_ = rosnode.serviceClient("set_joint_trajectory");
14 |
15 | trajectory_msgs::JointTrajectory jt;
16 |
17 | jt.header.stamp = ros::Time::now();
18 | jt.header.frame_id = "pr2::torso_lift_link";
19 |
20 | jt.joint_names.push_back("r_shoulder_pan_joint");
21 | jt.joint_names.push_back("r_shoulder_lift_joint");
22 | jt.joint_names.push_back("r_upper_arm_roll_joint");
23 | jt.joint_names.push_back("r_elbow_flex_joint");
24 | jt.joint_names.push_back("r_forearm_roll_joint");
25 | jt.joint_names.push_back("r_wrist_flex_joint");
26 | jt.joint_names.push_back("l_shoulder_pan_joint");
27 | jt.joint_names.push_back("l_shoulder_lift_joint");
28 | jt.joint_names.push_back("l_upper_arm_roll_joint");
29 | jt.joint_names.push_back("l_elbow_flex_joint");
30 | jt.joint_names.push_back("l_forearm_roll_joint");
31 | jt.joint_names.push_back("l_wrist_flex_joint");
32 |
33 | int n = 500;
34 | double dt = 0.1;
35 | double rps = 0.05;
36 | jt.points.resize(n);
37 | for (int i = 0; i < n; i++)
38 | {
39 | double theta = rps*2.0*M_PI*i*dt;
40 | double x1 = -0.5*sin(2*theta);
41 | double x2 = 0.5*sin(1*theta);
42 | jt.points[i].positions.push_back(x1);
43 | jt.points[i].positions.push_back(x2);
44 | jt.points[i].positions.push_back(3.14);
45 | jt.points[i].positions.push_back(-10.0);
46 | jt.points[i].positions.push_back(-0.2);
47 | jt.points[i].positions.push_back(-0.2);
48 | jt.points[i].positions.push_back(x1);
49 | jt.points[i].positions.push_back(x2);
50 | jt.points[i].positions.push_back(3.14);
51 | jt.points[i].positions.push_back(10.0);
52 | jt.points[i].positions.push_back(-0.2);
53 | jt.points[i].positions.push_back(-0.2);
54 | // set duration
55 | jt.points[i].time_from_start = ros::Duration(dt);
56 | ROS_INFO_NAMED("joint_trajectory_test", "test: angles[%d][%f, %f]",n,x1,x2);
57 | }
58 |
59 | // pub_.publish(jt); // use publisher
60 |
61 | gazebo_msgs::SetJointTrajectory sjt;
62 | sjt.request.joint_trajectory = jt;
63 | sjt.request.disable_physics_updates = false;
64 |
65 | ignition::math::Quaterniond r(0, 0, M_PI);
66 | geometry_msgs::Pose p;
67 | p.position.x = 0;
68 | p.position.y = 0;
69 | p.position.z = 0;
70 | p.orientation.x = r.X();
71 | p.orientation.y = r.Y();
72 | p.orientation.z = r.Z();
73 | p.orientation.w = r.W();
74 | sjt.request.model_pose = p;
75 | sjt.request.set_model_pose = true;
76 |
77 | srv_.call(sjt); // use service
78 |
79 | return 0;
80 | }
81 |
--------------------------------------------------------------------------------
/gazebo_plugins/include/gazebo_plugins/gazebo_ros_video.h:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2013 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 |
18 | /*
19 | * Desc: Video plugin for displaying ROS image topics on Ogre textures
20 | * Author: Piyush Khandelwal
21 | * Date: 26 July 2013
22 | */
23 |
24 | #ifndef GAZEBO_ROS_VIDEO_H
25 | #define GAZEBO_ROS_VIDEO_H
26 |
27 | #include
28 | #include
29 | #include
30 | #include
31 | #include
32 | #include
33 | #include
34 | #include
35 |
36 | #include
37 | #include
38 | #include
39 | #include
40 | #include
41 |
42 | namespace gazebo
43 | {
44 |
45 | class VideoVisual : public rendering::Visual
46 | {
47 | public:
48 | VideoVisual(
49 | const std::string &name, rendering::VisualPtr parent,
50 | int height, int width);
51 | virtual ~VideoVisual();
52 | void render(const cv::Mat& image);
53 | private:
54 | Ogre::TexturePtr texture_;
55 | int height_;
56 | int width_;
57 | };
58 |
59 | class GazeboRosVideo : public VisualPlugin
60 | {
61 | public:
62 |
63 | GazeboRosVideo();
64 | virtual ~GazeboRosVideo();
65 |
66 | void Load(rendering::VisualPtr parent, sdf::ElementPtr sdf);
67 | void processImage(const sensor_msgs::ImageConstPtr &msg);
68 |
69 | protected:
70 |
71 | virtual void UpdateChild();
72 |
73 | // Pointer to the model
74 | rendering::VisualPtr model_;
75 | // Pointer to the update event connection
76 | event::ConnectionPtr update_connection_;
77 |
78 | boost::shared_ptr video_visual_;
79 |
80 | cv_bridge::CvImagePtr image_;
81 | boost::mutex m_image_;
82 | bool new_image_available_;
83 |
84 | /// \brief A pointer to the ROS node. A node will be instantiated if it does not exist.
85 | ros::NodeHandle* rosnode_;
86 |
87 | // ROS Stuff
88 | ros::Subscriber camera_subscriber_;
89 | std::string robot_namespace_;
90 | std::string topic_name_;
91 |
92 | ros::CallbackQueue queue_;
93 | boost::thread callback_queue_thread_;
94 | void QueueThread();
95 |
96 | };
97 |
98 | }
99 |
100 | #endif
101 |
--------------------------------------------------------------------------------
/gazebo_plugins/src/gazebo_ros_elevator.cpp:
--------------------------------------------------------------------------------
1 | /*
2 | * Copyright 2015 Open Source Robotics Foundation
3 | *
4 | * Licensed under the Apache License, Version 2.0 (the "License");
5 | * you may not use this file except in compliance with the License.
6 | * You may obtain a copy of the License at
7 | *
8 | * http://www.apache.org/licenses/LICENSE-2.0
9 | *
10 | * Unless required by applicable law or agreed to in writing, software
11 | * distributed under the License is distributed on an "AS IS" BASIS,
12 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | * See the License for the specific language governing permissions and
14 | * limitations under the License.
15 | *
16 | */
17 | #include "gazebo_plugins/gazebo_ros_elevator.h"
18 |
19 | using namespace gazebo;
20 |
21 | GZ_REGISTER_MODEL_PLUGIN(GazeboRosElevator);
22 |
23 | /////////////////////////////////////////////////
24 | GazeboRosElevator::GazeboRosElevator()
25 | {
26 | }
27 |
28 | /////////////////////////////////////////////////
29 | GazeboRosElevator::~GazeboRosElevator()
30 | {
31 | this->queue_.clear();
32 | this->queue_.disable();
33 | this->rosnode_->shutdown();
34 | this->callbackQueueThread_.join();
35 |
36 | delete this->rosnode_;
37 | }
38 |
39 | /////////////////////////////////////////////////
40 | void GazeboRosElevator::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
41 | {
42 | // load parameters
43 | this->robotNamespace_ = "";
44 | if (_sdf->HasElement("robotNamespace"))
45 | {
46 | this->robotNamespace_ = _sdf->GetElement(
47 | "robotNamespace")->Get() + "/";
48 | }
49 |
50 | // Make sure the ROS node for Gazebo has already been initialized
51 | if (!ros::isInitialized())
52 | {
53 | ROS_FATAL_STREAM_NAMED("elevator", "A ROS node for Gazebo has not been initialized,"
54 | << "unable to load plugin. Load the Gazebo system plugin "
55 | << "'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
56 | return;
57 | }
58 |
59 | std::string topic = "elevator";
60 | if (_sdf->HasElement("topic"))
61 | topic = _sdf->Get("topic");
62 |
63 | ElevatorPlugin::Load(_parent, _sdf);
64 |
65 | this->rosnode_ = new ros::NodeHandle(this->robotNamespace_);
66 |
67 | ros::SubscribeOptions so =
68 | ros::SubscribeOptions::create(topic, 1,
69 | boost::bind(&GazeboRosElevator::OnElevator, this, boost::placeholders::_1),
70 | ros::VoidPtr(), &this->queue_);
71 |
72 | this->elevatorSub_ = this->rosnode_->subscribe(so);
73 |
74 | // start custom queue for elevator
75 | this->callbackQueueThread_ =
76 | boost::thread(boost::bind(&GazeboRosElevator::QueueThread, this));
77 | }
78 |
79 | /////////////////////////////////////////////////
80 | void GazeboRosElevator::OnElevator(const std_msgs::String::ConstPtr &_msg)
81 | {
82 | this->MoveToFloor(std::stoi(_msg->data));
83 | }
84 |
85 | /////////////////////////////////////////////////
86 | void GazeboRosElevator::QueueThread()
87 | {
88 | static const double timeout = 0.01;
89 |
90 | while (this->rosnode_->ok())
91 | this->queue_.callAvailable(ros::WallDuration(timeout));
92 | }
93 |
--------------------------------------------------------------------------------
/gazebo_plugins/src/hokuyo_node.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2009-2010, Willow Garage, Inc.
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of the Willow Garage nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | #include
36 | #include
37 |
38 | void callback(gazebo_plugins::HokuyoConfig &config, uint32_t level)
39 | {
40 | ROS_INFO_NAMED("hokuyo_node", "Reconfigure request : %f %f %i %i %i %s %i %s %f %i",
41 | config.min_ang, config.max_ang, (int)config.intensity, config.cluster, config.skip,
42 | config.port.c_str(), (int)config.calibrate_time, config.frame_id.c_str(), config.time_offset, (int)config.allow_unsafe_settings);
43 |
44 | // do nothing for now
45 |
46 | ROS_INFO_NAMED("hokuyo_node", "Reconfigure to : %f %f %i %i %i %s %i %s %f %i",
47 | config.min_ang, config.max_ang, (int)config.intensity, config.cluster, config.skip,
48 | config.port.c_str(), (int)config.calibrate_time, config.frame_id.c_str(), config.time_offset, (int)config.allow_unsafe_settings);
49 | }
50 |
51 | int main(int argc, char **argv)
52 | {
53 | ros::init(argc, argv, "hokuyo_node");
54 | dynamic_reconfigure::Server srv;
55 | dynamic_reconfigure::Server::CallbackType f = boost::bind(&callback, boost::placeholders::_1, boost::placeholders::_2);
56 | srv.setCallback(f);
57 | ROS_INFO_NAMED("hokuyo_node", "Starting to spin...");
58 | ros::spin();
59 | return 0;
60 | }
61 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro:
--------------------------------------------------------------------------------
1 |
2 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
69 |
70 |
71 |
72 |
--------------------------------------------------------------------------------
/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro:
--------------------------------------------------------------------------------
1 |
2 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
69 |
70 |
71 |
72 |
--------------------------------------------------------------------------------