├── .github ├── issue-branch.yml └── workflows │ ├── create_issue_branch.yml │ └── pythonapp.yml ├── .gitignore ├── .vscode └── pcg.vscode.code-snippets ├── 3rd-party-licenses.md ├── CONTRIBUTING.md ├── Dockerfile ├── LICENSE ├── NOTICE ├── README.md ├── docs ├── 404.html ├── assets │ ├── fonts │ │ ├── font-awesome.css │ │ ├── material-icons.css │ │ └── specimen │ │ │ ├── FontAwesome.ttf │ │ │ ├── FontAwesome.woff │ │ │ ├── FontAwesome.woff2 │ │ │ ├── MaterialIcons-Regular.ttf │ │ │ ├── MaterialIcons-Regular.woff │ │ │ └── MaterialIcons-Regular.woff2 │ ├── images │ │ ├── favicon.png │ │ └── icons │ │ │ ├── bitbucket.1b09e088.svg │ │ │ ├── github.f0b8504a.svg │ │ │ └── gitlab.6dd19c00.svg │ ├── javascripts │ │ ├── application.c33a9706.js │ │ ├── lunr │ │ │ ├── lunr.ar.js │ │ │ ├── lunr.da.js │ │ │ ├── lunr.de.js │ │ │ ├── lunr.du.js │ │ │ ├── lunr.es.js │ │ │ ├── lunr.fi.js │ │ │ ├── lunr.fr.js │ │ │ ├── lunr.hu.js │ │ │ ├── lunr.it.js │ │ │ ├── lunr.ja.js │ │ │ ├── lunr.jp.js │ │ │ ├── lunr.multi.js │ │ │ ├── lunr.nl.js │ │ │ ├── lunr.no.js │ │ │ ├── lunr.pt.js │ │ │ ├── lunr.ro.js │ │ │ ├── lunr.ru.js │ │ │ ├── lunr.stemmer.support.js │ │ │ ├── lunr.sv.js │ │ │ ├── lunr.th.js │ │ │ ├── lunr.tr.js │ │ │ ├── lunr.vi.js │ │ │ ├── tinyseg.js │ │ │ └── wordcut.js │ │ └── modernizr.86422ebf.js │ └── stylesheets │ │ ├── application-palette.a8b3c06d.css │ │ └── application.adb8469c.css ├── examples │ └── index.html ├── index.html ├── install │ └── index.html ├── reference │ ├── generators │ │ └── index.html │ ├── generators_components │ │ └── index.html │ ├── generators_constraints │ │ └── index.html │ ├── generators_engines │ │ └── index.html │ ├── generators_item_pickers │ │ └── index.html │ ├── generators_rules │ │ └── index.html │ ├── log │ │ └── index.html │ ├── parsers │ │ └── index.html │ ├── parsers_gazebo │ │ └── index.html │ ├── parsers_sdf │ │ └── index.html │ ├── parsers_sdf_config │ │ └── index.html │ ├── parsers_types │ │ └── index.html │ ├── parsers_urdf │ │ └── index.html │ ├── path │ │ └── index.html │ ├── simulation │ │ └── index.html │ ├── simulation_physics │ │ └── index.html │ ├── simulation_properties │ │ └── index.html │ ├── simulation_sensors │ │ └── index.html │ ├── task_manager │ │ └── index.html │ └── visualization │ │ └── index.html ├── scripts │ └── index.html ├── search │ └── search_index.json ├── single_room_generation │ └── index.html ├── sitemap.xml └── sitemap.xml.gz ├── examples ├── README.md ├── gen_add_texture_to_heightmap.ipynb ├── gen_fixed_pose_engine.ipynb ├── gen_generate_heightmaps.ipynb ├── gen_grid_map.ipynb ├── gen_model_from_factory_config.sh ├── gen_model_from_template.sh ├── gen_pattern_pose_engine.ipynb ├── gen_random_pose_engine.ipynb ├── gen_random_seed.ipynb ├── gen_set_max_num_objects_and_min_distance.ipynb ├── gen_workspaces.ipynb ├── images │ ├── crate.png │ ├── custom_biome.png │ ├── friction_test.png │ ├── gazebo_materials.png │ ├── gen_fixed_pose_engine.png │ ├── gen_random_pose_gen.png │ ├── generating_objects.png │ ├── heightmap_whittaker_moisture_0.png │ ├── heightmap_whittaker_moisture_1.png │ ├── heightmap_whittaker_moisture_2.png │ ├── heightmap_whittaker_moisture_3.png │ ├── heightmap_whittaker_moisture_4.png │ ├── heightmap_whittaker_moisture_5.png │ ├── heightmap_without_texture.png │ ├── jinja.jpeg │ ├── kobuki_jinja.png │ ├── sensors.png │ ├── sim_backpack_visual.png │ ├── sim_boxes.png │ ├── sim_boxes_after_wrench.png │ ├── sim_generated_crates.png │ ├── sim_kobuki_cmd.png │ ├── sim_mobile_base.png │ ├── sim_model_factory.png │ ├── sim_modified_mobile_base.png │ ├── sim_ur5_collision.png │ ├── sim_ur5_visual.png │ ├── sim_warehouse_robot_collision.png │ ├── sim_warehouse_robot_visual.png │ ├── transparency.png │ └── xkcd_materials.png ├── launch_pcg_world.sh ├── meshes │ ├── crate.stl │ ├── door.mtl │ ├── door.obj │ ├── door.png │ ├── monkey.stl │ └── monkey_offset.stl ├── model_factory │ ├── box_dynamic_model.yaml │ ├── box_factory_fixed_args.yaml │ ├── box_factory_lambda_args.yaml │ ├── box_static_model.yaml │ ├── cylinder_dynamic_model.yaml │ ├── cylinder_factory_fixed_args.yaml │ ├── cylinder_factory_lambda_args.yaml │ ├── cylinder_static_model.yaml │ ├── hinged_doors_from_mesh.yaml │ ├── hinged_doors_from_primitives.yaml │ ├── mesh_dynamic_model.yaml │ ├── mesh_static_model.yaml │ ├── sphere_dynamic_model.yaml │ ├── sphere_factory_fixed_args.yaml │ ├── sphere_factory_lambda_args.yaml │ └── sphere_static_model.yaml ├── model_generators │ └── full_crate.yml ├── models │ ├── pcg_jansport_backpack_red │ │ ├── materials │ │ │ └── textures │ │ │ │ └── backpack_diffuse.png │ │ ├── meshes │ │ │ └── backpack.dae │ │ ├── model.config │ │ └── model.sdf │ ├── pcg_warehouse_robot │ │ ├── materials │ │ │ └── textures │ │ │ │ └── robot.png │ │ ├── meshes │ │ │ ├── robot.mtl │ │ │ └── robot.obj │ │ ├── model.config │ │ └── model.sdf │ └── pcg_winding_valley_heightmap │ │ ├── materials │ │ └── textures │ │ │ ├── dirt_diffusespecular.png │ │ │ ├── flat_normal.png │ │ │ ├── fungus_diffusespecular.png │ │ │ ├── grass_diffusespecular.png │ │ │ └── heightmap.png │ │ ├── model.config │ │ └── model.sdf ├── robot_description │ └── kobuki │ │ ├── meshes │ │ └── kobuki │ │ │ ├── LICENSE │ │ │ ├── images │ │ │ ├── main_body.jpg │ │ │ └── wheel.jpg │ │ │ ├── main_body.mtl │ │ │ ├── main_body.obj │ │ │ ├── wheel.mtl │ │ │ └── wheel.obj │ │ └── sdf │ │ ├── actuators.sdf.jinja │ │ ├── kobuki.sdf.jinja │ │ ├── parameters.sdf.jinja │ │ ├── physics.sdf.jinja │ │ └── robot.sdf.jinja ├── sdf_parser_collisions.ipynb ├── sdf_parser_convert_from_sdf_file.ipynb ├── sdf_parser_geometries.ipynb ├── sdf_parser_links_joints_sensors.ipynb ├── sdf_parser_materials.ipynb ├── sdf_parser_models.ipynb ├── sdf_parser_physics_engines.ipynb ├── sdf_parser_plugins.ipynb ├── sdf_parser_visuals.ipynb ├── sdf_parser_world.ipynb ├── sim_creating_models_with_jupyter_notebooks.ipynb ├── sim_inspect_robot_description.ipynb ├── sim_inspection_of_gazebo_models.ipynb ├── sim_materials.ipynb ├── sim_meshes.ipynb ├── sim_model_factory.ipynb ├── sim_model_group_generators.ipynb ├── sim_objects.ipynb ├── sim_physics_engines.ipynb ├── sim_run_gazebo_with_process_timeout.ipynb ├── sim_run_gazebo_with_simulation_timeout.ipynb ├── sim_sensors.ipynb ├── sim_surface_collision_properties.ipynb ├── spawn_model_from_factory_config.sh ├── templates │ ├── models │ │ └── pcg_bouncy_ball.sdf.jinja │ └── world_generator │ │ └── physics │ │ ├── bullet.yml.jinja │ │ └── ode.yml.jinja ├── tm_gazebo_proxy.ipynb ├── tm_process_manager.ipynb ├── tm_stage_conditions.ipynb ├── urdf_parser_collision.ipynb ├── urdf_parser_geometries.ipynb ├── urdf_parser_links_joints_sensors.ipynb ├── urdf_parser_robots.ipynb ├── urdf_parser_visual.ipynb └── world_generator │ ├── physics │ ├── default_bullet.yml │ └── default_ode.yml │ └── worlds │ ├── bouncing_balls_ode.yml │ ├── empty_world_bullet.yml │ ├── empty_world_ode.yml │ ├── full_crates_ode.yml │ └── random_workspaces_ode.yml ├── pcg_gazebo ├── __init__.py ├── collection_managers │ ├── __init__.py │ ├── _collection_manager.py │ ├── assets_manager.py │ ├── constraints_manager.py │ ├── engine_manager.py │ ├── mesh_manager.py │ └── rules_manager.py ├── generators │ ├── __init__.py │ ├── _generator.py │ ├── biomes │ │ ├── __init__.py │ │ ├── biome.py │ │ └── whittaker_biome.py │ ├── collision_checker.py │ ├── constraints │ │ ├── __init__.py │ │ ├── constraint.py │ │ ├── tangent_constraint.py │ │ └── workspace_constraint.py │ ├── creators.py │ ├── engines │ │ ├── __init__.py │ │ ├── engine.py │ │ ├── fixed_pose_engine.py │ │ ├── pattern_engine.py │ │ └── random_pose_engine.py │ ├── heightmap_generator.py │ ├── item_pickers │ │ ├── __init__.py │ │ ├── _picker.py │ │ ├── random_picker.py │ │ ├── roulette_wheel_picker.py │ │ └── size_picker.py │ ├── mesh.py │ ├── model_group_generator.py │ ├── occupancy.py │ ├── patterns.py │ ├── rules │ │ ├── __init__.py │ │ ├── fixed_value.py │ │ ├── from_set.py │ │ ├── random.py │ │ ├── rule.py │ │ ├── uniform.py │ │ └── within_workspace.py │ ├── shapes.py │ └── world_generator.py ├── log.py ├── parsers │ ├── __init__.py │ ├── gazebo │ │ ├── __init__.py │ │ ├── kd.py │ │ ├── kp.py │ │ ├── material.py │ │ ├── max_contacts.py │ │ ├── max_vel.py │ │ ├── min_depth.py │ │ ├── mu1.py │ │ ├── mu2.py │ │ ├── provide_feedback.py │ │ ├── self_collide.py │ │ ├── stop_cfm.py │ │ └── stop_erp.py │ ├── sdf │ │ ├── __init__.py │ │ ├── accel.py │ │ ├── acceleration.py │ │ ├── accuracy.py │ │ ├── actor.py │ │ ├── allow_auto_disable.py │ │ ├── altimeter.py │ │ ├── always_on.py │ │ ├── ambient.py │ │ ├── angle.py │ │ ├── angular.py │ │ ├── angular_velocity.py │ │ ├── animation.py │ │ ├── atmosphere.py │ │ ├── attenuation.py │ │ ├── auto_start.py │ │ ├── axis.py │ │ ├── axis2.py │ │ ├── background.py │ │ ├── bias_mean.py │ │ ├── bias_stddev.py │ │ ├── blend.py │ │ ├── bounce.py │ │ ├── box.py │ │ ├── bullet.py │ │ ├── camera.py │ │ ├── cast_shadows.py │ │ ├── category_bitmask.py │ │ ├── center.py │ │ ├── cfm.py │ │ ├── cfm_damping.py │ │ ├── child.py │ │ ├── clip.py │ │ ├── clouds.py │ │ ├── coefficient.py │ │ ├── collide_bitmask.py │ │ ├── collide_without_contact.py │ │ ├── collide_without_contact_bitmask.py │ │ ├── collision.py │ │ ├── color.py │ │ ├── constant.py │ │ ├── constraints.py │ │ ├── contact.py │ │ ├── contact_max_correcting_vel.py │ │ ├── contact_surface_layer.py │ │ ├── cylinder.py │ │ ├── damping.py │ │ ├── delay_start.py │ │ ├── deletions.py │ │ ├── density.py │ │ ├── depth_camera.py │ │ ├── diffuse.py │ │ ├── direction.py │ │ ├── dissipation.py │ │ ├── distortion.py │ │ ├── dynamic_friction.py │ │ ├── dynamics.py │ │ ├── effort.py │ │ ├── elastic_modulus.py │ │ ├── elevation.py │ │ ├── emissive.py │ │ ├── empty.py │ │ ├── enable_wind.py │ │ ├── end.py │ │ ├── erp.py │ │ ├── fade_dist.py │ │ ├── falloff.py │ │ ├── far.py │ │ ├── fdir1.py │ │ ├── filename.py │ │ ├── fog.py │ │ ├── force_torque.py │ │ ├── format.py │ │ ├── frame.py │ │ ├── friction.py │ │ ├── friction2.py │ │ ├── friction_model.py │ │ ├── fullscreen.py │ │ ├── geometry.py │ │ ├── granularity.py │ │ ├── gravity.py │ │ ├── grid.py │ │ ├── gui.py │ │ ├── heading_deg.py │ │ ├── height.py │ │ ├── heightmap.py │ │ ├── horizontal.py │ │ ├── horizontal_fov.py │ │ ├── humidity.py │ │ ├── image.py │ │ ├── imu.py │ │ ├── include.py │ │ ├── inertia.py │ │ ├── inertial.py │ │ ├── inherit_yaw.py │ │ ├── initial_position.py │ │ ├── inner_angle.py │ │ ├── insertions.py │ │ ├── interpolate_x.py │ │ ├── iterations.py │ │ ├── iters.py │ │ ├── ixx.py │ │ ├── ixy.py │ │ ├── ixz.py │ │ ├── iyy.py │ │ ├── iyz.py │ │ ├── izz.py │ │ ├── joint.py │ │ ├── k1.py │ │ ├── k2.py │ │ ├── k3.py │ │ ├── kd.py │ │ ├── kinematic.py │ │ ├── kp.py │ │ ├── laser_retro.py │ │ ├── latitude_deg.py │ │ ├── length.py │ │ ├── light.py │ │ ├── lighting.py │ │ ├── limit.py │ │ ├── linear.py │ │ ├── linear_acceleration.py │ │ ├── linear_velocity.py │ │ ├── link.py │ │ ├── localization.py │ │ ├── longitude_deg.py │ │ ├── loop.py │ │ ├── lower.py │ │ ├── magnetic_field.py │ │ ├── mass.py │ │ ├── material.py │ │ ├── max.py │ │ ├── max_angle.py │ │ ├── max_contacts.py │ │ ├── max_dist.py │ │ ├── max_step_size.py │ │ ├── max_transient_velocity.py │ │ ├── max_vel.py │ │ ├── mean.py │ │ ├── mean_size.py │ │ ├── measure_direction.py │ │ ├── mesh.py │ │ ├── min.py │ │ ├── min_angle.py │ │ ├── min_depth.py │ │ ├── min_dist.py │ │ ├── min_height.py │ │ ├── min_step_size.py │ │ ├── model.py │ │ ├── mu.py │ │ ├── mu2.py │ │ ├── must_be_loop_joint.py │ │ ├── name.py │ │ ├── near.py │ │ ├── noise.py │ │ ├── normal.py │ │ ├── normal_map.py │ │ ├── ode.py │ │ ├── orientation_reference_frame.py │ │ ├── origin_visual.py │ │ ├── outer_angle.py │ │ ├── output.py │ │ ├── override_impact_capture_velocity.py │ │ ├── override_stiction_transition_velocity.py │ │ ├── p1.py │ │ ├── p2.py │ │ ├── parent.py │ │ ├── patch_radius.py │ │ ├── path.py │ │ ├── physics.py │ │ ├── plane.py │ │ ├── plastic_coef_restitution.py │ │ ├── plastic_impact_velocity.py │ │ ├── plugin.py │ │ ├── point.py │ │ ├── poissons_ratio.py │ │ ├── polyline.py │ │ ├── pos.py │ │ ├── pose.py │ │ ├── precision.py │ │ ├── precon_iters.py │ │ ├── pressure.py │ │ ├── projection_type.py │ │ ├── provide_feedback.py │ │ ├── quadratic.py │ │ ├── radius.py │ │ ├── range.py │ │ ├── rate.py │ │ ├── ray.py │ │ ├── real_time.py │ │ ├── real_time_factor.py │ │ ├── real_time_update_rate.py │ │ ├── resolution.py │ │ ├── restitution_coefficient.py │ │ ├── rolling_friction.py │ │ ├── samples.py │ │ ├── sampling.py │ │ ├── save.py │ │ ├── scale.py │ │ ├── scan.py │ │ ├── scene.py │ │ ├── script.py │ │ ├── sdf.py │ │ ├── self_collide.py │ │ ├── sensor.py │ │ ├── shader.py │ │ ├── shadows.py │ │ ├── sim_time.py │ │ ├── simbody.py │ │ ├── size.py │ │ ├── skin.py │ │ ├── sky.py │ │ ├── slip.py │ │ ├── slip1.py │ │ ├── slip2.py │ │ ├── soft_cfm.py │ │ ├── soft_erp.py │ │ ├── solver.py │ │ ├── sor.py │ │ ├── specular.py │ │ ├── speed.py │ │ ├── sphere.py │ │ ├── spherical_coordinates.py │ │ ├── split_impulse.py │ │ ├── split_impulse_penetration_threshold.py │ │ ├── spot.py │ │ ├── spring_reference.py │ │ ├── spring_stiffness.py │ │ ├── start.py │ │ ├── state.py │ │ ├── static.py │ │ ├── static_friction.py │ │ ├── stddev.py │ │ ├── stiffness.py │ │ ├── submesh.py │ │ ├── sunrise.py │ │ ├── sunset.py │ │ ├── surface.py │ │ ├── surface_model.py │ │ ├── surface_radius.py │ │ ├── temperature.py │ │ ├── temperature_gradient.py │ │ ├── texture.py │ │ ├── threshold.py │ │ ├── time.py │ │ ├── topic.py │ │ ├── torsional.py │ │ ├── track_visual.py │ │ ├── trajectory.py │ │ ├── transparency.py │ │ ├── type.py │ │ ├── update_rate.py │ │ ├── upper.py │ │ ├── urdf.py │ │ ├── uri.py │ │ ├── use_dynamic_moi_rescaling.py │ │ ├── use_model_frame.py │ │ ├── use_parent_model_frame.py │ │ ├── use_patch_radius.py │ │ ├── use_terrain_paging.py │ │ ├── velocity.py │ │ ├── vertical.py │ │ ├── vertical_position.py │ │ ├── vertical_velocity.py │ │ ├── view_controller.py │ │ ├── viscous_friction.py │ │ ├── visual.py │ │ ├── visualize.py │ │ ├── wall_time.py │ │ ├── waypoint.py │ │ ├── width.py │ │ ├── wind.py │ │ ├── world.py │ │ ├── world_frame_orientation.py │ │ ├── wrench.py │ │ ├── x.py │ │ ├── xyz.py │ │ ├── y.py │ │ └── z.py │ ├── sdf_config │ │ ├── __init__.py │ │ ├── author.py │ │ ├── description.py │ │ ├── email.py │ │ ├── model.py │ │ ├── name.py │ │ ├── sdf.py │ │ └── version.py │ ├── types │ │ ├── __init__.py │ │ ├── base.py │ │ ├── boolean.py │ │ ├── custom.py │ │ ├── integer.py │ │ ├── scalar.py │ │ ├── string.py │ │ └── vector.py │ └── urdf │ │ ├── __init__.py │ │ ├── actuator.py │ │ ├── axis.py │ │ ├── box.py │ │ ├── child.py │ │ ├── collision.py │ │ ├── color.py │ │ ├── cylinder.py │ │ ├── dynamics.py │ │ ├── gazebo.py │ │ ├── geometry.py │ │ ├── hardware_interface.py │ │ ├── inertia.py │ │ ├── inertial.py │ │ ├── joint.py │ │ ├── limit.py │ │ ├── link.py │ │ ├── mass.py │ │ ├── material.py │ │ ├── mechanical_reduction.py │ │ ├── mesh.py │ │ ├── mimic.py │ │ ├── origin.py │ │ ├── parent.py │ │ ├── robot.py │ │ ├── safety_controller.py │ │ ├── sphere.py │ │ ├── texture.py │ │ ├── transmission.py │ │ ├── type.py │ │ └── visual.py ├── path.py ├── random.py ├── simulation │ ├── __init__.py │ ├── actor.py │ ├── box.py │ ├── components │ │ ├── __init__.py │ │ ├── ground_plane.py │ │ ├── hinged_door.py │ │ ├── sun.py │ │ └── walls.py │ ├── cylinder.py │ ├── entity.py │ ├── joint.py │ ├── light.py │ ├── link.py │ ├── model.py │ ├── model_group.py │ ├── physics │ │ ├── __init__.py │ │ ├── bullet.py │ │ ├── ode.py │ │ ├── physics.py │ │ └── simbody.py │ ├── plane.py │ ├── polyline.py │ ├── properties │ │ ├── __init__.py │ │ ├── animation.py │ │ ├── axis.py │ │ ├── bounding_box.py │ │ ├── collision.py │ │ ├── footprint.py │ │ ├── geometry.py │ │ ├── heightmap.py │ │ ├── inertial.py │ │ ├── material.py │ │ ├── mesh.py │ │ ├── noise.py │ │ ├── plugin.py │ │ ├── pose.py │ │ ├── resources │ │ │ └── xkcd_rgb.txt │ │ ├── script.py │ │ ├── texture.py │ │ ├── trajectory.py │ │ ├── visual.py │ │ └── waypoint.py │ ├── sensors │ │ ├── __init__.py │ │ ├── camera.py │ │ ├── contact.py │ │ ├── imu.py │ │ ├── ray.py │ │ └── sensor.py │ ├── sphere.py │ └── world.py ├── task_manager │ ├── __init__.py │ ├── gazebo_proxy.py │ ├── process_manager.py │ ├── ros_config.py │ ├── server.py │ ├── simulation_timer.py │ ├── stage.py │ ├── task.py │ └── task_templates.py ├── templates │ ├── gazebo_ros_plugins.sdf.jinja │ ├── geometries.sdf.jinja │ ├── inertias.sdf.jinja │ ├── model.config.jinja │ ├── models.sdf.jinja │ ├── physics.sdf.jinja │ └── worlds.sdf.jinja ├── transformations.py ├── utils.py ├── version.py └── visualization.py ├── pydocmd.yml ├── scripts ├── README.md ├── pcg-generate-model-description ├── pcg-generate-occupancy-map ├── pcg-generate-sample-world-with-walls ├── pcg-generate-world ├── pcg-inspect-asset ├── pcg-install-gazebo-assets ├── pcg-list-gazebo-models ├── pcg-populate-world ├── pcg-preview-sdf ├── pcg-preview-urdf ├── pcg-print-xml-element ├── pcg-process-jinja-template ├── pcg-run-model-factory ├── pcg-sdf2urdf ├── pcg-sdflint ├── pcg-simulation-timer ├── pcg-spawn-sdf-model ├── pcg-start-gazebo-world ├── pcg-urdf2sdf ├── pcg-urdflint ├── pcg-view-gazebo-model └── pcg-view-mesh ├── setup.py ├── tests ├── gazebo_models │ ├── test_actor_relative_paths │ │ ├── LICENSE │ │ ├── SOURCE │ │ ├── meshes │ │ │ ├── gesture.bvh │ │ │ ├── moonwalk.dae │ │ │ ├── run.dae │ │ │ ├── sit.dae │ │ │ ├── sit_down.dae │ │ │ ├── sitting.dae │ │ │ ├── stand.dae │ │ │ ├── stand_up.dae │ │ │ ├── talk_a.dae │ │ │ ├── talk_b.dae │ │ │ └── walk.dae │ │ ├── model.config │ │ └── model.sdf │ ├── test_actor_walking │ │ ├── LICENSE │ │ ├── SOURCE │ │ ├── meshes │ │ │ └── walk.dae │ │ ├── model.config │ │ └── model.sdf │ ├── test_box │ │ ├── model.config │ │ └── model.sdf │ ├── test_joint_fixed │ │ ├── model.config │ │ └── model.sdf │ └── test_static_model │ │ ├── model.config │ │ └── model.sdf ├── jinja_sdf │ ├── cuboid_inertia.jinja │ ├── ellipsoid_inertia.jinja │ ├── hollow_sphere_inertia.jinja │ ├── inertia_solid_sphere.jinja │ ├── physics_default.jinja │ ├── physics_ode.jinja │ ├── solid_cylinder_inertia_axis_x.jinja │ ├── solid_cylinder_inertia_axis_y.jinja │ └── solid_cylinder_inertia_axis_z.jinja ├── meshes │ ├── cube.dae │ ├── cube.stl │ ├── monkey.dae │ ├── monkey.stl │ ├── monkey_offset.dae │ └── monkey_offset.stl ├── sdf │ ├── model_1_link_cube.sdf │ ├── sensor_imu_1.4.sdf │ ├── sensor_imu_1.5.sdf │ └── sensor_imu_1.6.sdf ├── test_actor.py ├── test_assets_manager.py ├── test_collision_checker.py ├── test_engine_and_constraint_managers.py ├── test_examples.py ├── test_heightmap.py ├── test_inertia.py ├── test_item_picker.py ├── test_jinja_sdf_file_generation.py ├── test_load_yaml.py ├── test_mesh_manager.py ├── test_mesh_property.py ├── test_model_factory.py ├── test_model_group.py ├── test_model_group_generator.py ├── test_occupancy_map.py ├── test_parser_gazebo.py ├── test_parser_sdf.py ├── test_parser_urdf.py ├── test_patterns.py ├── test_pose.py ├── test_random.py ├── test_resolve_paths.py ├── test_rules_manager.py ├── test_sdf.py ├── test_sdf2urdf_script.py ├── test_sdflint_script.py ├── test_simulation_objects.py ├── test_urdf.py ├── test_urdf2sdf_script.py ├── test_urdflint_script.py ├── test_world.py ├── test_world_generator.py ├── urdf │ ├── gazebo_default_joint.urdf │ ├── gazebo_default_link.urdf │ ├── gazebo_imu_1_4.urdf │ ├── gazebo_imu_1_5.urdf │ ├── gazebo_imu_1_6.urdf │ ├── gazebo_material_single_link_mult_visual.urdf │ ├── gazebo_material_single_link_single_visual.urdf │ ├── geometry_box.urdf │ ├── geometry_cylinder.urdf │ ├── geometry_mesh.urdf │ ├── geometry_sphere.urdf │ ├── link_empty.urdf │ ├── link_simple.urdf │ └── robot_simple_gazebo_reference.urdf ├── worlds │ ├── SOURCE │ ├── actor_gazebo_gazebo_9_13.world │ ├── animated_box_gazebo_9_13.world │ ├── attach_lights_gazebo_9_13.world │ ├── blank_gazebo_9_13.world │ ├── blink_visual_gazebo_9_13.world │ ├── cafe_gazebo_9_13.world │ ├── camera_intrinsics_gazebo_9_13.world │ ├── empty_world_gazebo_9_13.world │ ├── test_pcg_empty.world │ ├── test_pcg_example.world │ └── test_pcg_simple_door.world └── yaml │ ├── dummy.yaml │ ├── include_dummy.yaml │ ├── include_ros_package.yaml │ ├── include_wrong_ros_package.yaml │ └── wrong_extension.ym └── tutorials ├── install.md └── single_room_generation.md /.github/issue-branch.yml: -------------------------------------------------------------------------------- 1 | branches: 2 | - label: enhancement 3 | prefix: feature/ 4 | - label: bug 5 | prefix: bugfix/ 6 | - label: documentation 7 | prefix: docs/ 8 | - label: maintenance 9 | prefix: maint/ -------------------------------------------------------------------------------- /.github/workflows/create_issue_branch.yml: -------------------------------------------------------------------------------- 1 | 2 | on: 3 | issues: 4 | types: [assigned] 5 | issue_comment: 6 | types: [created] 7 | 8 | jobs: 9 | create_issue_branch_job: 10 | runs-on: ubuntu-latest 11 | steps: 12 | - name: Create Issue Branch 13 | uses: robvanderleek/create-issue-branch@main 14 | env: 15 | GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} 16 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | *.pyc 3 | __pycache__ 4 | .pytest_cache 5 | .ipynb_checkpoints 6 | .vscode/c_cpp_properties.json 7 | .vscode/settings.json 8 | .vscode/launch.json 9 | 10 | # Packaging files 11 | build/ 12 | dist/ 13 | *.egg 14 | *.egg-info/ 15 | 16 | # Test files 17 | venv/ 18 | 19 | # Documentation files 20 | site/ 21 | _pydocmd -------------------------------------------------------------------------------- /docs/assets/fonts/material-icons.css: -------------------------------------------------------------------------------- 1 | /*! 2 | * Licensed under the Apache License, Version 2.0 (the "License"); you may not 3 | * use this file except in compliance with the License. You may obtain a copy 4 | * of the License at: 5 | * 6 | * http://www.apache.org/licenses/LICENSE-2.0 7 | * 8 | * UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING, SOFTWARE 9 | * DISTRIBUTED UNDER THE LICENSE IS DISTRIBUTED ON AN "AS IS" BASIS, 10 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, EITHER EXPRESS OR IMPLIED. 11 | * SEE THE LICENSE FOR THE SPECIFIC LANGUAGE GOVERNING PERMISSIONS AND 12 | * LIMITATIONS UNDER THE LICENSE. 13 | */@font-face{font-family:"Material Icons";font-style:normal;font-weight:400;src:local("Material Icons"),local("MaterialIcons-Regular"),url("specimen/MaterialIcons-Regular.woff2") format("woff2"),url("specimen/MaterialIcons-Regular.woff") format("woff"),url("specimen/MaterialIcons-Regular.ttf") format("truetype")} -------------------------------------------------------------------------------- /docs/assets/fonts/specimen/FontAwesome.ttf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/docs/assets/fonts/specimen/FontAwesome.ttf -------------------------------------------------------------------------------- /docs/assets/fonts/specimen/FontAwesome.woff: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/docs/assets/fonts/specimen/FontAwesome.woff -------------------------------------------------------------------------------- /docs/assets/fonts/specimen/FontAwesome.woff2: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/docs/assets/fonts/specimen/FontAwesome.woff2 -------------------------------------------------------------------------------- /docs/assets/fonts/specimen/MaterialIcons-Regular.ttf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/docs/assets/fonts/specimen/MaterialIcons-Regular.ttf -------------------------------------------------------------------------------- /docs/assets/fonts/specimen/MaterialIcons-Regular.woff: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/docs/assets/fonts/specimen/MaterialIcons-Regular.woff -------------------------------------------------------------------------------- /docs/assets/fonts/specimen/MaterialIcons-Regular.woff2: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/docs/assets/fonts/specimen/MaterialIcons-Regular.woff2 -------------------------------------------------------------------------------- /docs/assets/images/favicon.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/docs/assets/images/favicon.png -------------------------------------------------------------------------------- /docs/assets/images/icons/github.f0b8504a.svg: -------------------------------------------------------------------------------- 1 | -------------------------------------------------------------------------------- /docs/assets/javascripts/lunr/lunr.jp.js: -------------------------------------------------------------------------------- 1 | module.exports=require("./lunr.ja"); -------------------------------------------------------------------------------- /docs/assets/javascripts/lunr/lunr.multi.js: -------------------------------------------------------------------------------- 1 | !function(e,t){"function"==typeof define&&define.amd?define(t):"object"==typeof exports?module.exports=t():t()(e.lunr)}(this,function(){return function(o){o.multiLanguage=function(){for(var e=Array.prototype.slice.call(arguments),t=e.join("-"),i="",r=[],n=[],s=0;s 2 | 3 | JanSport Backpack Red 4 | 1.0 5 | model.sdf 6 | 7 | 8 | Cole Biesemeyer 9 | cole@openrobotics.org 10 | 11 | 12 | 13 | Red JanSport backpack. 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /examples/models/pcg_jansport_backpack_red/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | true 5 | 6 | 7 | 8 | 9 | model://pcg_jansport_backpack_red/meshes/backpack.dae 10 | 11 | 12 | 13 | 14 | 15 | 16 | model://pcg_jansport_backpack_red/meshes/backpack.dae 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /examples/models/pcg_warehouse_robot/materials/textures/robot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/examples/models/pcg_warehouse_robot/materials/textures/robot.png -------------------------------------------------------------------------------- /examples/models/pcg_warehouse_robot/meshes/robot.mtl: -------------------------------------------------------------------------------- 1 | # Blender MTL File: 'None' 2 | # Material Count: 1 3 | 4 | newmtl MobileRobot 5 | Ns 225.000000 6 | Ka 1.000000 1.000000 1.000000 7 | Kd 0.800000 0.800000 0.800000 8 | Ks 0.500000 0.500000 0.500000 9 | Ke 0.000000 0.000000 0.000000 10 | Ni 1.450000 11 | d 1.000000 12 | illum 2 13 | map_Kd ../materials/textures/robot.png 14 | -------------------------------------------------------------------------------- /examples/models/pcg_warehouse_robot/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Warehouse Robot 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Nate Koenig 10 | nate@osrfoundation.org 11 | 12 | 13 | 14 | Cole Biesemeyer 15 | 16 | 17 | 18 | A generic warehouse robot. 19 | 20 | 21 | -------------------------------------------------------------------------------- /examples/models/pcg_winding_valley_heightmap/materials/textures/dirt_diffusespecular.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/examples/models/pcg_winding_valley_heightmap/materials/textures/dirt_diffusespecular.png -------------------------------------------------------------------------------- /examples/models/pcg_winding_valley_heightmap/materials/textures/flat_normal.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/examples/models/pcg_winding_valley_heightmap/materials/textures/flat_normal.png -------------------------------------------------------------------------------- /examples/models/pcg_winding_valley_heightmap/materials/textures/fungus_diffusespecular.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/examples/models/pcg_winding_valley_heightmap/materials/textures/fungus_diffusespecular.png -------------------------------------------------------------------------------- /examples/models/pcg_winding_valley_heightmap/materials/textures/grass_diffusespecular.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/examples/models/pcg_winding_valley_heightmap/materials/textures/grass_diffusespecular.png -------------------------------------------------------------------------------- /examples/models/pcg_winding_valley_heightmap/materials/textures/heightmap.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/examples/models/pcg_winding_valley_heightmap/materials/textures/heightmap.png -------------------------------------------------------------------------------- /examples/models/pcg_winding_valley_heightmap/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Winding Valley Heightmap 5 | 1.0 6 | model.sdf 7 | 8 | 9 | Nate Koenig 10 | nate@osrfoundation.com 11 | 12 | 13 | 14 | A winding valley heightmap. 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /examples/robot_description/kobuki/meshes/kobuki/images/main_body.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/examples/robot_description/kobuki/meshes/kobuki/images/main_body.jpg -------------------------------------------------------------------------------- /examples/robot_description/kobuki/meshes/kobuki/images/wheel.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/examples/robot_description/kobuki/meshes/kobuki/images/wheel.jpg -------------------------------------------------------------------------------- /examples/robot_description/kobuki/meshes/kobuki/main_body.mtl: -------------------------------------------------------------------------------- 1 | # Blender MTL File: 'None' 2 | # Material Count: 1 3 | 4 | newmtl _1_-_Default.001 5 | Ns 94.117647 6 | Ka 1.000000 1.000000 1.000000 7 | Kd 0.640000 0.640000 0.640000 8 | Ks 50.000000 50.000000 50.000000 9 | Ke 0.000000 0.000000 0.000000 10 | Ni 1.000000 11 | d 1.000000 12 | illum 2 13 | map_Kd images/main_body.jpg 14 | -------------------------------------------------------------------------------- /examples/robot_description/kobuki/meshes/kobuki/wheel.mtl: -------------------------------------------------------------------------------- 1 | # Blender MTL File: 'None' 2 | # Material Count: 1 3 | 4 | newmtl _1_-_Default 5 | Ns 225.000000 6 | Ka 1.000000 1.000000 1.000000 7 | Kd 0.800000 0.800000 0.800000 8 | Ks 0.500000 0.500000 0.500000 9 | Ke 0.0 0.0 0.0 10 | Ni 1.450000 11 | d 1.000000 12 | illum 2 13 | map_Kd images/wheel.jpg 14 | -------------------------------------------------------------------------------- /examples/templates/world_generator/physics/bullet.yml.jinja: -------------------------------------------------------------------------------- 1 | engine: bullet 2 | args: 3 | max_step_size: {{ max_step_size|default(0.001, true) }} 4 | real_time_factor: {{ real_time_factor|default(1, true) }} 5 | real_time_update_rate: {{ real_time_update_rate|default(1000, true) }} 6 | max_contacts: {{ max_contacts|default(20, true) }} 7 | min_step_size: {{ min_step_size|default(0.001, true) }} 8 | iters: {{ iters|default(50, true) }} 9 | sor: {{ sor|default(1.3, true) }} 10 | cfm: {{ cfm|default(0, true) }} 11 | erp: {{ erp|default(0.2, true) }} 12 | contact_surface_layer: {{ contact_surface_layer|default(0.001, true) }} 13 | split_impulse: {{ split_impulse|default(true, true) }} 14 | split_impulse_penetration_threshold: {{ split_impulse_penetration_threshold|default(-0.01, true) }} -------------------------------------------------------------------------------- /examples/templates/world_generator/physics/ode.yml.jinja: -------------------------------------------------------------------------------- 1 | engine: ode 2 | args: 3 | max_step_size: {{ max_step_size|default(0.001, true) }} 4 | real_time_factor: {{ real_time_factor|default(1, true) }} 5 | real_time_update_rate: {{ real_time_update_rate|default(1000, true) }} 6 | max_contacts: {{ max_contacts|default(20, true) }} 7 | min_step_size: {{ min_step_size|default(0.0001, true) }} 8 | iters: {{ iters|default(50, true) }} 9 | sor: {{ sor|default(1.3, true) }} 10 | type: {{ type|default('quick', true) }} 11 | precon_iters: {{ precon_iters|default(0, true) }} 12 | use_dynamic_moi_rescaling: {{ use_dynamic_moi_rescaling|default(false, true) }} 13 | friction_model: {{ friction_model|default('pyramid_model', true) }} 14 | cfm: {{ cfm|default(0, true) }} 15 | erp: {{ erp|default(0.2, true) }} 16 | contact_surface_layer: {{ contact_surface_layer|default(0.001, true) }} 17 | contact_max_correcting_vel: {{ contact_max_correcting_vel|default(100, true) }} -------------------------------------------------------------------------------- /examples/world_generator/physics/default_bullet.yml: -------------------------------------------------------------------------------- 1 | engine: bullet 2 | args: 3 | max_step_size: 0.001 4 | real_time_factor: 1 5 | real_time_update_rate: 1000 6 | max_contacts: 20 7 | min_step_size: 0.001 8 | iters: 50 9 | sor: 1.3 10 | cfm: 0 11 | erp: 0.2 12 | contact_surface_layer: 0.001 13 | split_impulse: True 14 | split_impulse_penetration_threshold: -0.01 -------------------------------------------------------------------------------- /examples/world_generator/physics/default_ode.yml: -------------------------------------------------------------------------------- 1 | engine: ode 2 | args: 3 | max_step_size: 0.001 4 | real_time_factor: 1 5 | real_time_update_rate: 1000 6 | max_contacts: 20 7 | min_step_size: 0.0001 8 | iters: 50 9 | sor: 1.3 10 | type: quick 11 | precon_iters: 0 12 | use_dynamic_moi_rescaling: false 13 | friction_model: pyramid_model 14 | cfm: 0 15 | erp: 0.2 16 | contact_surface_layer: 0.001 17 | contact_max_correcting_vel: 100 -------------------------------------------------------------------------------- /examples/world_generator/worlds/empty_world_bullet.yml: -------------------------------------------------------------------------------- 1 | name: empty_world_bullet 2 | engines: 3 | - engine_name: fixed_pose 4 | models: 5 | - ground_plane 6 | poses: 7 | - [0, 0, 0, 0, 0, 0] 8 | - engine_name: fixed_pose 9 | models: 10 | - sun 11 | poses: 12 | - [0, 0, 10, 0, 0, 0] 13 | physics: !include ../physics/default_bullet.yml -------------------------------------------------------------------------------- /examples/world_generator/worlds/empty_world_ode.yml: -------------------------------------------------------------------------------- 1 | name: empty_world_ode 2 | engines: 3 | - engine_name: fixed_pose 4 | models: 5 | - ground_plane 6 | poses: 7 | - [0, 0, 0, 0, 0, 0] 8 | - engine_name: fixed_pose 9 | models: 10 | - sun 11 | poses: 12 | - [0, 0, 10, 0, 0, 0] 13 | physics: !include ../physics/default_ode.yml 14 | -------------------------------------------------------------------------------- /examples/world_generator/worlds/full_crates_ode.yml: -------------------------------------------------------------------------------- 1 | name: full_crates_ode 2 | assets: 3 | ground_plane: 4 | - ground_plane 5 | assets: 6 | - tag: full_crate 7 | type: model_generator 8 | description: !include ../../model_generators/full_crate.yml 9 | engines: 10 | - engine_name: fixed_pose 11 | models: 12 | - ground_plane 13 | poses: 14 | - [0, 0, 0, 0, 0, 0] 15 | - engine_name: fixed_pose 16 | models: 17 | - sun 18 | poses: 19 | - [0, 0, 10, 0, 0, 0] 20 | - engine_name: fixed_pose 21 | models: 22 | - full_crate 23 | poses: 24 | - [1.5, 0, 0, 0, 0, 0] 25 | - [0, 0, 0, 0, 0, 0] 26 | - [-1.5, 0, 0, 0, 0, 0] 27 | physics: ../physics/default_ode.yml 28 | -------------------------------------------------------------------------------- /pcg_gazebo/generators/biomes/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from .biome import Biome 17 | from .whittaker_biome import WhittakerBiome 18 | 19 | __all__ = [ 20 | 'Biome', 21 | 'WhittakerBiome' 22 | ] 23 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/acceleration.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class Acceleration(XMLVector): 19 | _NAME = 'acceleration' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[0, 0, 0, 0, 0, 0]): 23 | super(Acceleration, self).__init__(size=6) 24 | self.value = default 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/accuracy.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Accuracy(XMLScalar): 20 | _NAME = 'accuracy' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.001): 24 | super(Accuracy, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/allow_auto_disable.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class AllowAutoDisable(XMLBoolean): 20 | _NAME = 'allow_auto_disable' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(AllowAutoDisable, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/always_on.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class AlwaysOn(XMLBoolean): 20 | _NAME = 'always_on' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(AlwaysOn, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/ambient.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class Ambient(XMLVector): 19 | _NAME = 'ambient' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[0, 0, 0, 1]): 23 | super(Ambient, self).__init__( 24 | 4, min_value=0, max_value=1) 25 | self._default = default 26 | self._value = default 27 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/auto_start.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class AutoStart(XMLBoolean): 20 | _NAME = 'auto_start' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=True): 24 | super(AutoStart, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/cast_shadows.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class CastShadows(XMLBoolean): 20 | _NAME = 'cast_shadows' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=True): 24 | super(CastShadows, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/category_bitmask.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 16 | 17 | 18 | class CategoryBitmask(XMLInteger): 19 | _NAME = 'category_bitmask' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=65535): 23 | super(CategoryBitmask, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/cfm.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class CFM(XMLScalar): 20 | _NAME = 'cfm' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(CFM, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/cfm_damping.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class CFMDamping(XMLBoolean): 19 | _NAME = 'cfm_damping' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=False): 23 | super(CFMDamping, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/child.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Child(XMLString): 20 | _NAME = 'child' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default='none'): 24 | super(Child, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/collide_bitmask.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 16 | 17 | 18 | class CollideBitmask(XMLInteger): 19 | _NAME = 'collide_bitmask' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=65535): 23 | super(CollideBitmask, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/collide_without_contact.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class CollideWithoutContact(XMLBoolean): 19 | _NAME = 'collide_without_contact' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=False): 23 | super(CollideWithoutContact, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/collide_without_contact_bitmask.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class CollideWithoutContactBitmask(XMLBoolean): 19 | _NAME = 'collide_without_contact_bitmask' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=True): 23 | super(CollideWithoutContactBitmask, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/color.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class Color(XMLVector): 19 | _NAME = 'color' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[1, 1, 1, 1]): 23 | super(Color, self).__init__(4) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/contact_max_correcting_vel.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class ContactMaxCorrectingVel(XMLScalar): 20 | _NAME = 'contact_max_correcting_vel' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=100): 24 | super(ContactMaxCorrectingVel, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/contact_surface_layer.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class ContactSurfaceLayer(XMLScalar): 20 | _NAME = 'contact_surface_layer' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.001): 24 | super(ContactSurfaceLayer, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/damping.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Damping(XMLScalar): 20 | _NAME = 'damping' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(Damping, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/delay_start.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class DelayStart(XMLScalar): 20 | _NAME = 'delay_start' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(DelayStart, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/dissipation.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Dissipation(XMLScalar): 20 | _NAME = 'dissipation' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=100): 24 | super(Dissipation, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/dynamic_friction.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class DynamicFriction(XMLScalar): 19 | _NAME = 'dynamic_friction' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0.9): 23 | super(DynamicFriction, self).__init__(default, min_value=0) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/effort.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Effort(XMLScalar): 20 | _NAME = 'effort' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=-1): 24 | super(Effort, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/elevation.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Elevation(XMLScalar): 19 | _NAME = 'elevation' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(Elevation, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/empty.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Empty(XMLString): 20 | _NAME = 'empty' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self): 24 | super(Empty, self).__init__('') 25 | 26 | def _set_value(self, value): 27 | pass 28 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/enable_wind.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class EnableWind(XMLBoolean): 20 | _NAME = 'enable_wind' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(EnableWind, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/erp.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class ERP(XMLScalar): 20 | _NAME = 'erp' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.2): 24 | super(ERP, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/fade_dist.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class FadeDist(XMLScalar): 19 | _NAME = 'fade_dist' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(FadeDist, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/far.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Far(XMLScalar): 20 | _NAME = 'far' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(Far, self).__init__(default, min_value=0) 25 | 26 | def _set_value(self, value): 27 | XMLScalar._set_value(self, value) 28 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/filename.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Filename(XMLString): 20 | _NAME = 'filename' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default='none'): 24 | super(Filename, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/friction2.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Friction2(XMLScalar): 20 | _NAME = 'friction2' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=1): 24 | super(Friction2, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/fullscreen.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class Fullscreen(XMLBoolean): 19 | _NAME = 'fullscreen' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=False): 23 | super(Fullscreen, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/granularity.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 17 | 18 | 19 | class Granularity(XMLInteger): 20 | _NAME = 'granularity' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=1): 24 | super(Granularity, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/grid.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class Grid(XMLBoolean): 19 | _NAME = 'grid' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=True): 23 | super(Grid, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/heading_deg.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class HeadingDeg(XMLScalar): 19 | _NAME = 'heading_deg' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(HeadingDeg, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/height.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Height(XMLScalar): 20 | _NAME = 'height' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=1): 24 | super(Height, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/horizontal_fov.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class HorizontalFOV(XMLScalar): 20 | _NAME = 'horizontal_fov' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=1.047): 24 | super(HorizontalFOV, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/inherit_yaw.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class InheritYaw(XMLBoolean): 19 | _NAME = 'inherit_yaw' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=False): 23 | super(InheritYaw, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/initial_position.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class InitialPosition(XMLScalar): 20 | _NAME = 'initial_position' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(InitialPosition, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/interpolate_x.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class InterpolateX(XMLBoolean): 20 | _NAME = 'interpolate_x' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(InterpolateX, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/iterations.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 16 | 17 | 18 | class Iterations(XMLInteger): 19 | _NAME = 'iterations' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(Iterations, self).__init__( 24 | default=default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/iters.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 17 | 18 | 19 | class Iters(XMLInteger): 20 | _NAME = 'iters' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=50): 24 | super(Iters, self).__init__(default, min_value=1) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/ixx.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class IXX(XMLScalar): 20 | _NAME = 'ixx' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(IXX, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/ixy.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class IXY(XMLScalar): 20 | _NAME = 'ixy' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(IXY, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/ixz.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class IXZ(XMLScalar): 20 | _NAME = 'ixz' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(IXZ, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/iyy.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class IYY(XMLScalar): 20 | _NAME = 'iyy' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(IYY, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/iyz.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class IYZ(XMLScalar): 20 | _NAME = 'iyz' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(IYZ, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/izz.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class IZZ(XMLScalar): 20 | _NAME = 'izz' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(IZZ, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/k1.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class K1(XMLScalar): 20 | _NAME = 'k1' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(K1, self).__init__(default) 25 | 26 | def _set_value(self, value): 27 | assert value >= 0 28 | XMLScalar._set_value(self, value) 29 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/k2.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class K2(XMLScalar): 20 | _NAME = 'k2' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(K2, self).__init__(default) 25 | 26 | def _set_value(self, value): 27 | assert value >= 0 28 | XMLScalar._set_value(self, value) 29 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/k3.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class K3(XMLScalar): 20 | _NAME = 'k3' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(K3, self).__init__(default) 25 | 26 | def _set_value(self, value): 27 | assert value >= 0 28 | XMLScalar._set_value(self, value) 29 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/kinematic.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class Kinematic(XMLBoolean): 20 | _NAME = 'kinematic' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(Kinematic, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/latitude_deg.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class LatitudeDeg(XMLScalar): 19 | _NAME = 'latitude_deg' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(LatitudeDeg, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/length.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Length(XMLScalar): 20 | _NAME = 'length' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self): 24 | super(Length, self).__init__(min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/lighting.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class Lighting(XMLBoolean): 20 | _NAME = 'lighting' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(Lighting, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/linear.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Linear(XMLScalar): 19 | _NAME = 'linear' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0, min_value=None, max_value=None): 23 | super(Linear, self).__init__( 24 | default, min_value=min_value, 25 | max_value=max_value) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/linear_velocity.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class LinearVelocity(XMLVector): 19 | _NAME = 'linear_velocity' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[0, 0, 0]): 23 | super(LinearVelocity, self).__init__(size=3) 24 | self.value = default 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/longitude_deg.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class LongitudeDeg(XMLScalar): 19 | _NAME = 'longitude_deg' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(LongitudeDeg, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/loop.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class Loop(XMLBoolean): 20 | _NAME = 'loop' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(Loop, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/lower.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Lower(XMLScalar): 20 | _NAME = 'lower' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=-1e16): 24 | super(Lower, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/magnetic_field.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class MagneticField(XMLVector): 19 | _NAME = 'magnetic_field' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[6e-6, 2.3e-5, -4.2e-5]): 23 | super(MagneticField, self).__init__(size=3) 24 | self.value = default 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/mass.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Mass(XMLScalar): 20 | _NAME = 'mass' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self): 24 | super(Mass, self).__init__(min_value=1e-10) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/max.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Max(XMLScalar): 20 | _NAME = 'max' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(Max, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/max_angle.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class MaxAngle(XMLScalar): 20 | _NAME = 'max_angle' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(MaxAngle, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/max_contacts.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 17 | 18 | 19 | class MaxContacts(XMLInteger): 20 | _NAME = 'max_contacts' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=20): 24 | super(MaxContacts, self).__init__(default, min_value=1) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/max_dist.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class MaxDist(XMLScalar): 19 | _NAME = 'max_dist' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(MaxDist, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/max_step_size.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class MaxStepSize(XMLScalar): 20 | _NAME = 'max_step_size' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.001): 24 | super(MaxStepSize, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/max_transient_velocity.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class MaxTransientVelocity(XMLScalar): 20 | _NAME = 'max_transient_velocity' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.01): 24 | super(MaxTransientVelocity, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/max_vel.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class MaxVel(XMLScalar): 20 | _NAME = 'max_vel' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.01): 24 | super(MaxVel, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/mean.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Mean(XMLScalar): 20 | _NAME = 'mean' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self): 24 | super(Mean, self).__init__(min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/mean_size.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class MeanSize(XMLScalar): 19 | _NAME = 'mean_size' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(MeanSize, self).__init__( 24 | default, min_value=0, max_value=1) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/min.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Min(XMLScalar): 20 | _NAME = 'min' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(Min, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/min_angle.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class MinAngle(XMLScalar): 20 | _NAME = 'min_angle' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(MinAngle, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/min_depth.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class MinDepth(XMLScalar): 20 | _NAME = 'min_depth' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(MinDepth, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/min_dist.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class MinDist(XMLScalar): 19 | _NAME = 'min_dist' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(MinDist, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/min_height.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class MinHeight(XMLScalar): 19 | _NAME = 'min_height' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(MinHeight, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/min_step_size.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class MinStepSize(XMLScalar): 20 | _NAME = 'min_step_size' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.0001): 24 | super(MinStepSize, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/must_be_loop_joint.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class MustBeLoopJoint(XMLBoolean): 20 | _NAME = 'must_be_loop_joint' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(MustBeLoopJoint, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/name.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Name(XMLString): 20 | _NAME = 'name' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default='none'): 24 | super(Name, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/near.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Near(XMLScalar): 20 | _NAME = 'near' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(Near, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/normal_map.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class NormalMap(XMLString): 20 | _NAME = 'normal_map' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=''): 24 | super(NormalMap, self).__init__(default=default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/origin_visual.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class OriginVisual(XMLBoolean): 19 | _NAME = 'origin_visual' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=True): 23 | super(OriginVisual, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/outer_angle.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class OuterAngle(XMLScalar): 20 | _NAME = 'outer_angle' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(OuterAngle, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/output.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Output(XMLString): 20 | _NAME = 'output' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default='depths'): 24 | super(Output, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/p1.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class P1(XMLScalar): 20 | _NAME = 'p1' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(P1, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/p2.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class P2(XMLScalar): 20 | _NAME = 'p2' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(P2, self).__init__(default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/parent.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Parent(XMLString): 20 | _NAME = 'parent' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default='parent'): 24 | super(Parent, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/patch_radius.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class PatchRadius(XMLScalar): 20 | _NAME = 'patch_radius' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(PatchRadius, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/path.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Path(XMLString): 20 | _NAME = 'path' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default='__default__'): 24 | super(Path, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/plastic_coef_restitution.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class PlasticCoefRestitution(XMLScalar): 20 | _NAME = 'plastic_coef_restitution' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.5): 24 | super(PlasticCoefRestitution, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/plastic_impact_velocity.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class PlasticImpactVelocity(XMLScalar): 20 | _NAME = 'plastic_impact_velocity' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.5): 24 | super(PlasticImpactVelocity, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/point.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 17 | 18 | 19 | class Point(XMLVector): 20 | _NAME = 'point' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, vec_length=2): 24 | super(Point, self).__init__(vec_length) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/poissons_ratio.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class PoissonsRatio(XMLScalar): 19 | _NAME = 'poissons_ratio' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0.3): 23 | super(PoissonsRatio, self).__init__( 24 | default, min_value=-1, max_value=0.5) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/pos.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class Pos(XMLVector): 19 | _NAME = 'pos' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[0, 0, 0]): 23 | super(Pos, self).__init__(3) 24 | self._value = default 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/precon_iters.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 17 | 18 | 19 | class PreConIters(XMLInteger): 20 | _NAME = 'precon_iters' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(PreConIters, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/pressure.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Pressure(XMLScalar): 19 | _NAME = 'pressure' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=101325.0): 23 | super(Pressure, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/provide_feedback.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class ProvideFeedback(XMLBoolean): 20 | _NAME = 'provide_feedback' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(ProvideFeedback, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/quadratic.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Quadratic(XMLScalar): 19 | _NAME = 'quadratic' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(Quadratic, self).__init__(default, min_value=0) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/radius.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Radius(XMLScalar): 19 | _NAME = 'radius' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(Radius, self).__init__(default, min_value=0) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/real_time.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class RealTime(XMLVector): 19 | _NAME = 'real_time' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[0, 0]): 23 | super(RealTime, self).__init__( 24 | size=2, min_value=0) 25 | self.value = default 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/real_time_factor.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class RealTimeFactor(XMLScalar): 19 | _NAME = 'real_time_factor' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=1): 23 | super(RealTimeFactor, self).__init__( 24 | default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/real_time_update_rate.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class RealTimeUpdateRate(XMLScalar): 19 | _NAME = 'real_time_update_rate' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=1): 23 | super(RealTimeUpdateRate, self).__init__( 24 | default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/resolution.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Resolution(XMLScalar): 20 | _NAME = 'resolution' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(Resolution, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/restitution_coefficient.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class RestitutionCoefficient(XMLScalar): 20 | _NAME = 'restitution_coefficient' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(RestitutionCoefficient, self).__init__( 25 | default) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/rolling_friction.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class RollingFriction(XMLScalar): 20 | _NAME = 'rolling_friction' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=1): 24 | super(RollingFriction, self).__init__( 25 | default, min_value=0, max_value=1) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/samples.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 17 | 18 | 19 | class Samples(XMLInteger): 20 | _NAME = 'samples' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=640): 24 | super(Samples, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/sampling.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLInteger 16 | 17 | 18 | class Sampling(XMLInteger): 19 | _NAME = 'sampling' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=2): 23 | super(Sampling, self).__init__( 24 | default=default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/self_collide.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class SelfCollide(XMLBoolean): 19 | _NAME = 'self_collide' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=False): 23 | super(SelfCollide, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/shadows.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class Shadows(XMLBoolean): 19 | _NAME = 'shadows' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=True): 23 | super(Shadows, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/sim_time.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class SimTime(XMLVector): 19 | _NAME = 'sim_time' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[0, 0]): 23 | super(SimTime, self).__init__( 24 | size=2, min_value=0) 25 | self.value = default 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/soft_cfm.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class SoftCFM(XMLScalar): 20 | _NAME = 'soft_cfm' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(SoftCFM, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/soft_erp.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class SoftERP(XMLScalar): 20 | _NAME = 'soft_erp' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.2): 24 | super(SoftERP, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/sor.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Sor(XMLScalar): 19 | _NAME = 'sor' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=1.3): 23 | super(Sor, self).__init__( 24 | default=default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/speed.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Speed(XMLScalar): 19 | _NAME = 'speed' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0.6): 23 | super(Speed, self).__init__( 24 | default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/split_impulse.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class SplitImpulse(XMLBoolean): 20 | _NAME = 'split_impulse' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=True): 24 | super(SplitImpulse, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/spring_reference.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class SpringReference(XMLScalar): 20 | _NAME = 'spring_reference' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(SpringReference, self).__init__( 25 | default=0, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/spring_stiffness.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class SpringStiffness(XMLScalar): 20 | _NAME = 'spring_stiffness' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(SpringStiffness, self).__init__( 25 | default=0, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/start.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Start(XMLScalar): 19 | _NAME = 'start' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(Start, self).__init__(default, min_value=0) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/static.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class Static(XMLBoolean): 20 | _NAME = 'static' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(Static, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/static_friction.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class StaticFriction(XMLScalar): 20 | _NAME = 'static_friction' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0.9): 24 | super(StaticFriction, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/stddev.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class StdDev(XMLScalar): 19 | _NAME = 'stddev' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self): 23 | super(StdDev, self).__init__(min_value=0) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/stiffness.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Stiffness(XMLScalar): 20 | _NAME = 'stiffness' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=1e8): 24 | super(Stiffness, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/sunrise.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Sunrise(XMLScalar): 19 | _NAME = 'sunrise' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(Sunrise, self).__init__( 24 | default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/sunset.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Sunset(XMLScalar): 19 | _NAME = 'sunset' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(Sunset, self).__init__( 24 | default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/surface_radius.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class SurfaceRadius(XMLScalar): 19 | _NAME = 'surface_radius' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(SurfaceRadius, self).__init__( 24 | default, min_value=0) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/temperature.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Temperature(XMLScalar): 19 | _NAME = 'temperature' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=288.15): 23 | super(Temperature, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/temperature_gradient.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class TemperatureGradient(XMLScalar): 19 | _NAME = 'temperature_gradient' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=-0.0065): 23 | super(TemperatureGradient, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/threshold.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Threshold(XMLScalar): 20 | _NAME = 'threshold' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(Threshold, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/time.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 16 | 17 | 18 | class Time(XMLScalar): 19 | _NAME = 'time' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=0): 23 | super(Time, self).__init__(default) 24 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/topic.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Topic(XMLString): 20 | _NAME = 'topic' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default='none'): 24 | super(Topic, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/transparency.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Transparency(XMLScalar): 20 | _NAME = 'transparency' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(Transparency, self).__init__( 25 | default=0, min_value=0, max_value=1) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/type.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Type(XMLString): 20 | _NAME = 'type' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=''): 24 | super(Type, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/update_rate.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class UpdateRate(XMLScalar): 20 | _NAME = 'update_rate' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(UpdateRate, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/upper.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Upper(XMLScalar): 20 | _NAME = 'upper' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=1e16): 24 | super(Upper, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/uri.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class URI(XMLString): 20 | _NAME = 'uri' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default='__default__'): 24 | super(URI, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/use_dynamic_moi_rescaling.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class UseDynamicMOIRescaling(XMLBoolean): 20 | _NAME = 'use_dynamic_moi_rescaling' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(UseDynamicMOIRescaling, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/use_model_frame.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class UseModelFrame(XMLBoolean): 20 | _NAME = 'use_model_frame' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(UseModelFrame, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/use_parent_model_frame.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class UseParentModelFrame(XMLBoolean): 20 | _NAME = 'use_parent_model_frame' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(UseParentModelFrame, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/use_patch_radius.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class UsePatchRadius(XMLBoolean): 20 | _NAME = 'use_patch_radius' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=True): 24 | super(UsePatchRadius, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/use_terrain_paging.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 16 | 17 | 18 | class UseTerrainPaging(XMLBoolean): 19 | _NAME = 'use_terrain_paging' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=False): 23 | super(UseTerrainPaging, self).__init__( 24 | default=default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/viscous_friction.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class ViscousFriction(XMLScalar): 20 | _NAME = 'viscous_friction' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=0): 24 | super(ViscousFriction, self).__init__( 25 | default, min_value=0) 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/visualize.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLBoolean 17 | 18 | 19 | class Visualize(XMLBoolean): 20 | _NAME = 'visualize' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=False): 24 | super(Visualize, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/wall_time.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class WallTime(XMLVector): 19 | _NAME = 'wall_time' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[0, 0]): 23 | super(WallTime, self).__init__( 24 | size=2, min_value=0) 25 | self.value = default 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/width.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class Width(XMLScalar): 20 | _NAME = 'width' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=320): 24 | super(Width, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/wrench.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2020 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 16 | 17 | 18 | class Wrench(XMLVector): 19 | _NAME = 'wrench' 20 | _TYPE = 'sdf' 21 | 22 | def __init__(self, default=[0, 0, 0, 0, 0, 0]): 23 | super(Wrench, self).__init__(size=6) 24 | self.value = default 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf/xyz.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLVector 17 | 18 | 19 | class XYZ(XMLVector): 20 | _NAME = 'xyz' 21 | _TYPE = 'sdf' 22 | 23 | def __init__(self, default=[0, 0, 1]): 24 | super(XYZ, self).__init__(3) 25 | self.value = default 26 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf_config/description.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Description(XMLString): 20 | _NAME = 'description' 21 | _TYPE = 'sdf_config' 22 | 23 | def __init__(self, default='none'): 24 | super(Description, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf_config/email.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class EMail(XMLString): 20 | _NAME = 'email' 21 | _TYPE = 'sdf_config' 22 | 23 | def __init__(self, default='none'): 24 | super(EMail, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf_config/name.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Name(XMLString): 20 | _NAME = 'name' 21 | _TYPE = 'sdf_config' 22 | 23 | def __init__(self, default='none'): 24 | super(Name, self).__init__(default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/sdf_config/version.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Version(XMLString): 20 | _NAME = 'version' 21 | _TYPE = 'sdf_config' 22 | 23 | def __init__(self, default='none'): 24 | super(Version, self).__init__(default) 25 | 26 | def _set_value(self, value): 27 | self._value = str(value) 28 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/urdf/hardware_interface.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class HardwareInterface(XMLString): 20 | _NAME = 'hardwareInterface' 21 | _TYPE = 'urdf' 22 | 23 | def __init__(self, default='EffortJointInterface'): 24 | XMLString.__init__(self, default=default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/urdf/mechanical_reduction.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLScalar 17 | 18 | 19 | class MechanicalReduction(XMLScalar): 20 | _NAME = 'mechanicalReduction' 21 | _TYPE = 'urdf' 22 | 23 | def __init__(self, default=1): 24 | XMLScalar.__init__(self, default=default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/parsers/urdf/type.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from ..types import XMLString 17 | 18 | 19 | class Type(XMLString): 20 | _NAME = 'type' 21 | _TYPE = 'urdf' 22 | 23 | def __init__(self, default='transmission_interface/SimpleTransmission'): 24 | XMLString.__init__(self, default=default) 25 | -------------------------------------------------------------------------------- /pcg_gazebo/simulation/components/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from .ground_plane import GroundPlane 17 | from .hinged_door import HingedDoor 18 | from .sun import Sun 19 | from .walls import Walls 20 | 21 | __all__ = [ 22 | 'GroundPlane', 23 | 'HingedDoor', 24 | 'Sun', 25 | 'Walls' 26 | ] 27 | -------------------------------------------------------------------------------- /pcg_gazebo/simulation/physics/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from .physics import Physics 17 | from .ode import ODE 18 | from .bullet import Bullet 19 | from .simbody import Simbody 20 | 21 | 22 | __all__ = [ 23 | 'Physics', 24 | 'ODE', 25 | 'Bullet', 26 | 'Simbody' 27 | ] 28 | -------------------------------------------------------------------------------- /pcg_gazebo/simulation/sensors/__init__.py: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 2 | # For information on the respective copyright owner see the NOTICE file 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 | from .camera import Camera 17 | from .contact import Contact 18 | from .imu import IMU 19 | from .ray import Ray 20 | from .sensor import Sensor 21 | 22 | 23 | __all__ = [ 24 | 'Camera', 25 | 'Contact', 26 | 'IMU', 27 | 'Ray', 28 | 'Sensor' 29 | ] 30 | -------------------------------------------------------------------------------- /pcg_gazebo/templates/model.config.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% set model_name = model_name|default('model', true) %} 3 | {% set version = version|default(1.0, true) %} 4 | {% set sdf_version = sdf_version|default('1.6', true) %} 5 | {% set sdf_filename = sdf_filename|default('model.sdf', true) %} 6 | {% set author_name = author_name|default('author', true) %} 7 | {% set author_email = author_email|default('author@email.com', true) %} 8 | {% set description = description|default('', true) %} 9 | 10 | 11 | {{ model_name }} 12 | {{ version }} 13 | {{ sdf_filename }} 14 | 15 | 16 | {{ author_name }} 17 | {{ author_email}} 18 | 19 | 20 | {{ description }} 21 | 22 | -------------------------------------------------------------------------------- /pcg_gazebo/version.py: -------------------------------------------------------------------------------- 1 | __version__ = '0.7.12' 2 | -------------------------------------------------------------------------------- /scripts/pcg-list-gazebo-models: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | # Copyright (c) 2019 - The Procedural Generation for Gazebo authors 3 | # For information on the respective copyright owner see the NOTICE file 4 | # 5 | # Licensed under the Apache License, Version 2.0 (the "License"); 6 | # you may not use this file except in compliance with the License. 7 | # You may obtain a copy of the License at 8 | # 9 | # http://www.apache.org/licenses/LICENSE-2.0 10 | # 11 | # Unless required by applicable law or agreed to in writing, software 12 | # distributed under the License is distributed on an "AS IS" BASIS, 13 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 14 | # See the License for the specific 15 | from __future__ import print_function 16 | from pcg_gazebo.simulation import load_gazebo_models 17 | 18 | 19 | if __name__ == '__main__': 20 | models = load_gazebo_models() 21 | for tag in sorted(models): 22 | print('{}: {}'.format(tag, models[tag]['path'])) 23 | -------------------------------------------------------------------------------- /tests/gazebo_models/test_actor_relative_paths/SOURCE: -------------------------------------------------------------------------------- 1 | https://app.ignitionrobotics.org/chapulina/fuel/models/actor%20-%20relative%20paths -------------------------------------------------------------------------------- /tests/gazebo_models/test_actor_relative_paths/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | actor 5 | 1.0 6 | model.sdf 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | An animated actor. 15 | 16 | 17 | -------------------------------------------------------------------------------- /tests/gazebo_models/test_actor_walking/SOURCE: -------------------------------------------------------------------------------- 1 | https://app.ignitionrobotics.org/chapulina/fuel/models/Walking%20actor -------------------------------------------------------------------------------- /tests/gazebo_models/test_actor_walking/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Actor walk 5 | 1.0 6 | model.sdf 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | An animated walking actor. 15 | 16 | 17 | -------------------------------------------------------------------------------- /tests/gazebo_models/test_box/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | test_box 4 | 1.0 5 | model.sdf 6 | 7 | awesome name 8 | awesome@mail.com 9 | 10 | awesome model 11 | 12 | -------------------------------------------------------------------------------- /tests/gazebo_models/test_joint_fixed/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | test_joints 4 | 1.0 5 | model.sdf 6 | 7 | awesome name 8 | awesome@mail.com 9 | 10 | awesome model 11 | 12 | -------------------------------------------------------------------------------- /tests/gazebo_models/test_static_model/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | test_static_model 4 | 1.0 5 | model.sdf 6 | 7 | awesome name 8 | awesome@mail.com 9 | 10 | awesome model 11 | 12 | -------------------------------------------------------------------------------- /tests/jinja_sdf/cuboid_inertia.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'inertias'|find_sdf_template as inertias %} 3 | {{ inertias.cuboid_inertia(mass, length_x, length_y, length_z) }} -------------------------------------------------------------------------------- /tests/jinja_sdf/ellipsoid_inertia.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'inertias'|find_sdf_template as inertias %} 3 | {{ inertias.ellipsoid_inertia(mass, axis_length_x, axis_length_y, axis_length_z) }} -------------------------------------------------------------------------------- /tests/jinja_sdf/hollow_sphere_inertia.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'inertias'|find_sdf_template as inertias %} 3 | {{ inertias.hollow_sphere_inertia(mass, radius) }} -------------------------------------------------------------------------------- /tests/jinja_sdf/inertia_solid_sphere.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'inertias'|find_sdf_template as inertias %} 3 | {{ inertias.solid_sphere_inertia(mass, radius) }} -------------------------------------------------------------------------------- /tests/jinja_sdf/physics_default.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'physics'|find_sdf_template as physics %} 3 | {{ physics.physics() }} -------------------------------------------------------------------------------- /tests/jinja_sdf/physics_ode.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'physics'|find_sdf_template as physics %} 3 | {{ physics.physics( 4 | name=label, 5 | default=0, 6 | type=engine, 7 | max_step_size=max_step_size, 8 | real_time_factor=real_time_factor, 9 | real_time_update_rate=real_time_update_rate, 10 | max_contacts=max_contacts, 11 | ode_solver_type=ode_solver_type, 12 | ode_min_step_size=ode_min_step_size, 13 | ode_iters=ode_iters, 14 | ode_precon_iters=ode_precon_iters, 15 | ode_sor=ode_sor, 16 | ode_use_dynamic_moi_rescaling=ode_use_dynamic_moi_rescaling, 17 | ode_friction_model=ode_friction_model, 18 | ode_cfm=ode_cfm, 19 | ode_erp=ode_erp, 20 | ode_contact_max_correcting_vel=ode_contact_max_correcting_vel, 21 | ode_contact_surface_layer=ode_contact_surface_layer) 22 | }} -------------------------------------------------------------------------------- /tests/jinja_sdf/solid_cylinder_inertia_axis_x.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'inertias'|find_sdf_template as inertias %} 3 | {{ inertias.solid_cylinder_inertia(mass, radius, length, "x") }} -------------------------------------------------------------------------------- /tests/jinja_sdf/solid_cylinder_inertia_axis_y.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'inertias'|find_sdf_template as inertias %} 3 | {{ inertias.solid_cylinder_inertia(mass, radius, length, "y") }} -------------------------------------------------------------------------------- /tests/jinja_sdf/solid_cylinder_inertia_axis_z.jinja: -------------------------------------------------------------------------------- 1 | 2 | {% import 'inertias'|find_sdf_template as inertias %} 3 | {{ inertias.solid_cylinder_inertia(mass, radius, length, "z") }} -------------------------------------------------------------------------------- /tests/meshes/monkey.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/tests/meshes/monkey.stl -------------------------------------------------------------------------------- /tests/meshes/monkey_offset.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/tests/meshes/monkey_offset.stl -------------------------------------------------------------------------------- /tests/sdf/model_1_link_cube.sdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/tests/sdf/model_1_link_cube.sdf -------------------------------------------------------------------------------- /tests/urdf/gazebo_default_joint.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 0.1 4 | 0.3 5 | 0 6 | -------------------------------------------------------------------------------- /tests/urdf/gazebo_default_link.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 1.0 4 | 1.0 5 | 1000000.0 6 | 100.0 7 | 0.001 8 | 1.0 9 | 0 10 | 15 11 | Gazebo/Yellow 12 | -------------------------------------------------------------------------------- /tests/urdf/gazebo_material_single_link_single_visual.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | Gazebo/Blue 23 | 24 | -------------------------------------------------------------------------------- /tests/urdf/geometry_box.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /tests/urdf/geometry_cylinder.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /tests/urdf/geometry_mesh.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /tests/urdf/geometry_sphere.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /tests/urdf/link_empty.urdf: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /tests/urdf/link_simple.urdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /tests/worlds/SOURCE: -------------------------------------------------------------------------------- 1 | *_gazebo_9_13.world: https://github.com/osrf/gazebo/tree/gazebo9/worlds -------------------------------------------------------------------------------- /tests/worlds/test_pcg_empty.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://sun 7 | 8 | 9 | 10 | model://ground_plane 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /tests/worlds/test_pcg_example.world: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | model://sun 7 | 8 | 9 | 10 | model://ground_plane 11 | 12 | 13 | 14 | 0 0 0.5 0 0 0 15 | true 16 | 17 | 18 | 19 | 20 | 1 1 1 21 | 22 | 23 | 24 | 25 | 26 | 27 | 1 1 1 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /tests/yaml/dummy.yaml: -------------------------------------------------------------------------------- 1 | a: 1 2 | b: 2 3 | c: !include include_dummy.yaml -------------------------------------------------------------------------------- /tests/yaml/include_dummy.yaml: -------------------------------------------------------------------------------- 1 | test: a test 2 | -------------------------------------------------------------------------------- /tests/yaml/include_ros_package.yaml: -------------------------------------------------------------------------------- 1 | a: !find pcg_libraries/test/yaml/include_dummy.yaml -------------------------------------------------------------------------------- /tests/yaml/include_wrong_ros_package.yaml: -------------------------------------------------------------------------------- 1 | a: !find aBc/dummy.yaml -------------------------------------------------------------------------------- /tests/yaml/wrong_extension.ym: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/boschresearch/pcg_gazebo/346394cdb720c9df5ca1d1df6dac7ad0b6e436fc/tests/yaml/wrong_extension.ym --------------------------------------------------------------------------------