Skip to content

Commit

Permalink
Merge branch 'ign-gazebo3' into ahcorde/3/scene_info_sensors
Browse files Browse the repository at this point in the history
  • Loading branch information
ahcorde authored Feb 16, 2022
2 parents d5447fd + 7b4fcda commit 00b066e
Show file tree
Hide file tree
Showing 50 changed files with 11,332 additions and 6 deletions.
80 changes: 80 additions & 0 deletions examples/worlds/elevator.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
<?xml version="1.0" ?>
<!--
Ignition Gazebo elevator plugin demo
Try sending a command:
ign topic -t "/model/elevator/cmd" -m ignition.msgs.Int32 -p "data: 2"
Listen to state:
ign topic -e -t /model/elevator/state
-->
<sdf version="1.6">
<world name="elevator_world">

<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-sensors-system"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<include>
<uri>https://fuel.ignitionrobotics.org/1.0/nlamprian/models/Elevator</uri>
</include>

</world>
</sdf>
5 changes: 0 additions & 5 deletions src/gui/plugins/shapes/Shapes.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,6 @@ namespace ignition::gazebo
{
class ShapesPrivate
{
/// \brief Ignition communication node.
public: transport::Node node;

/// \brief Transform control service name
public: std::string service;
};
}

Expand Down
10 changes: 9 additions & 1 deletion src/systems/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ function(gz_add_system system_name)

set(options)
set(oneValueArgs)
set(multiValueArgs SOURCES PUBLIC_LINK_LIBS PRIVATE_LINK_LIBS PRIVATE_COMPILE_DEFS)
set(multiValueArgs SOURCES PUBLIC_LINK_LIBS PRIVATE_INCLUDE_DIRS PRIVATE_LINK_LIBS PRIVATE_COMPILE_DEFS)

cmake_parse_arguments(gz_add_system "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN})

Expand All @@ -47,6 +47,13 @@ function(gz_add_system system_name)
ignition-plugin${IGN_PLUGIN_VER}::register
)

if(gz_add_system_PRIVATE_INCLUDE_DIRS)
target_include_directories(${system_target}
PRIVATE
${gz_add_system_PRIVATE_INCLUDE_DIRS}
)
endif()

if(gz_add_system_PRIVATE_COMPILE_DEFS)
target_compile_definitions(${system_target}
PRIVATE
Expand Down Expand Up @@ -82,6 +89,7 @@ add_subdirectory(contact)
add_subdirectory(camera_video_recorder)
add_subdirectory(detachable_joint)
add_subdirectory(diff_drive)
add_subdirectory(elevator)
add_subdirectory(imu)
add_subdirectory(joint_controller)
add_subdirectory(joint_position_controller)
Expand Down
12 changes: 12 additions & 0 deletions src/systems/elevator/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
gz_add_system(elevator
SOURCES
Elevator.cc
utils/DoorTimer.cc
utils/JointMonitor.cc
PUBLIC_LINK_LIBS
ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER}
PRIVATE_INCLUDE_DIRS
vender/afsm/include
vender/metapushkin/include
)
Loading

0 comments on commit 00b066e

Please sign in to comment.