Skip to content

Commit

Permalink
Pass ros_distro in CMakeLists.txt instaed of checking it in jinja_gen…
Browse files Browse the repository at this point in the history
….py (PX4#712)

* pass ros distro in CMakeList instead of checking it in jinja_gen.py

* generate ROS model with option GENERATE_ROS_MODELS. change option BUILD_ROS_INTERFACE to BUILD_ROS_PLUGINS

* argument build_ros_interface change to generate_ros_models, remove ros_distro and just check ros_version
  • Loading branch information
ldg810 authored Mar 20, 2021
1 parent 1b1afca commit 1f339cd
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 23 deletions.
30 changes: 20 additions & 10 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ include(GNUInstallDirs)
#######################

option(BUILD_GSTREAMER_PLUGIN "enable gstreamer plugin" ON)
option(BUILD_ROS_INTERFACE "Enable building ROS dependent plugins" OFF)
option(BUILD_ROS_PLUGINS "Enable building ROS dependent plugins" OFF)
option(GENERATE_ROS_MODELS "Generate model sdf for ROS environment" OFF)

option(SEND_VISION_ESTIMATION_DATA "Send Mavlink VISION_POSITION_ESTIMATE msgs" OFF)
option(SEND_ODOMETRY_DATA "Send Mavlink ODOMETRY msgs" OFF)
Expand Down Expand Up @@ -103,7 +104,7 @@ add_subdirectory( external/OpticalFlow OpticalFlow )
set( OpticalFlow_LIBS "OpticalFlow" )

# for ROS subscribers and publishers
if (BUILD_ROS_INTERFACE)
if (BUILD_ROS_PLUGINS)
find_package(geometry_msgs REQUIRED)
find_package(roscpp REQUIRED)
find_package(sensor_msgs REQUIRED)
Expand Down Expand Up @@ -270,12 +271,21 @@ function(glob_generate target file_glob)
set(out_file ${CMAKE_CURRENT_SOURCE_DIR}/${file_name})
string(REGEX REPLACE ".sdf" ".sdf" out_file ${out_file})
if (${file_ext} STREQUAL "jinja")
add_custom_command(OUTPUT ${out_file}
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file} ${CMAKE_CURRENT_SOURCE_DIR}
DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file}
VERBATIM
)
if(GENERATE_ROS_MODELS)
add_custom_command(OUTPUT ${out_file}
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file} ${CMAKE_CURRENT_SOURCE_DIR} --generate_ros_models true
DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file}
VERBATIM
)
else()
add_custom_command(OUTPUT ${out_file}
COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file} ${CMAKE_CURRENT_SOURCE_DIR}
DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py ${in_file}
VERBATIM
)
endif()
list(APPEND gen_files_${target} ${out_file})
string(REGEX REPLACE "${CMAKE_CURRENT_SOURCE_DIR}/" "" gitignore_str ${in_file})
string(REGEX REPLACE ".jinja" "" gitignore_str ${gitignore_str})
Expand Down Expand Up @@ -392,9 +402,9 @@ foreach(plugin ${plugins})
endforeach()
target_link_libraries(gazebo_opticalflow_plugin ${OpticalFlow_LIBS})

# If BUILD_ROS_INTERFACE set to ON, build plugins that have ROS dependencies
# If BUILD_ROS_PLUGINS set to ON, build plugins that have ROS dependencies
# Current plugins that can be used with ROS interface: gazebo_motor_failure_plugin
if (BUILD_ROS_INTERFACE)
if (BUILD_ROS_PLUGINS)
add_library(gazebo_motor_failure_plugin SHARED src/gazebo_motor_failure_plugin.cpp)
target_link_libraries(gazebo_motor_failure_plugin ${GAZEBO_libraries} ${roscpp_LIBRARIES})
list(APPEND plugins gazebo_motor_failure_plugin)
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ With *catkin*, the unit tests are enabled by default.

```bash
# After setting up the catkin workspace
catkin build -j4 -l4 -DBUILD_ROS_INTERFACE=ON
catkin build -j4 -l4 -DBUILD_ROS_PLUGINS=ON
cd build/mavlink_sitl_gazebo/
catkin run_tests
```
Expand Down
2 changes: 1 addition & 1 deletion models/depth_camera/depth_camera.sdf.jinja
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
</geometry>
</visual>
<sensor name="depth_camera" type="depth">
{% if ros2_distro in ['dashing', 'eloquent', 'foxy'] %}
{% if ros_version == 2 %}
<always_on>0</always_on>
<update_rate>20</update_rate>
<camera name="camera_name">
Expand Down
25 changes: 14 additions & 11 deletions scripts/jinja_gen.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,13 @@ def get_file_contents(filepath):
with open(filepath, 'rb') as f:
return f.read()

def str2bool(v):
if v.lower() in ('yes', 'true', 't', 'y', '1'):
return True
elif v.lower() in ('no', 'false', 'f', 'n', '0'):
return False
else:
raise argparse.ArgumentTypeError('Boolean value expected.')

if __name__ == "__main__":
parser = argparse.ArgumentParser()
Expand All @@ -31,20 +38,16 @@ def get_file_contents(filepath):
parser.add_argument('--gst_udp_port', default=5600, help="Gstreamer UDP port for SITL")
parser.add_argument('--video_uri', default=5600, help="Mavlink camera URI for SITL")
parser.add_argument('--mavlink_cam_udp_port', default=14530, help="Mavlink camera UDP port for SITL")
parser.add_argument('--ros2-distro', default='', dest='ros2_distro', type=str,
help="ROS2 distro, only required if generating the agent for usage with ROS2 nodes, by default empty")
parser.add_argument('--generate_ros_models', default=False, dest='generate_ros_models', type=str2bool,
help="required if generating the agent for usage with ROS nodes, by default false")
args = parser.parse_args()
env = jinja2.Environment(loader=jinja2.FileSystemLoader(args.env_dir))
template = env.get_template(os.path.relpath(args.filename, args.env_dir))

# get ROS 2 version, if exists
ros2_distro = ''
ros_version = os.environ.get('ROS_VERSION')
if ros_version == '2':
if args.ros2_distro != '':
ros2_distro = args.ros2_distro
else:
ros2_distro = os.environ.get('ROS_DISTRO')
# get ROS version, if generate_ros_models is true.
ros_version = 0
if args.generate_ros_models:
ros_version = os.environ.get('ROS_VERSION')

# create dictionary with useful modules etc.
try:
Expand All @@ -66,7 +69,7 @@ def get_file_contents(filepath):
'video_uri': args.video_uri, \
'mavlink_cam_udp_port': args.mavlink_cam_udp_port, \
'hil_mode': args.hil_mode, \
'ros2_distro': ros2_distro}
'ros_version': ros_version}

result = template.render(d)

Expand Down

0 comments on commit 1f339cd

Please sign in to comment.