diff --git a/.gitignore b/.gitignore index 18aa814dbc..e5704e8481 100644 --- a/.gitignore +++ b/.gitignore @@ -26,3 +26,4 @@ models/rover/rover.sdf models/tiltrotor/tiltrotor.sdf models/boat/boat.sdf models/typhoon_h480/typhoon_h480.sdf +models/depth_camera/depth_camera.sdf diff --git a/models/depth_camera/depth_camera.sdf b/models/depth_camera/depth_camera.sdf.jinja similarity index 65% rename from models/depth_camera/depth_camera.sdf rename to models/depth_camera/depth_camera.sdf.jinja index b027cc8777..8f5b57fb92 100644 --- a/models/depth_camera/depth_camera.sdf +++ b/models/depth_camera/depth_camera.sdf.jinja @@ -1,3 +1,4 @@ + @@ -24,6 +25,38 @@ + {% if ros2_distro in ['dashing', 'eloquent', 'foxy'] %} + 0 + 20 + + 1.02974 + + R8G8B8 + 64 + 48 + + + 0.5 + 18 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 +
0.5 0.5
+
+
+ + + camera + camera_link + 0.07 + 0.1 + 12 + + {% else %} 20 1.02974 @@ -55,6 +88,7 @@ 0.0 0.0 + {% endif %}
diff --git a/scripts/jinja_gen.py b/scripts/jinja_gen.py index c638dd57c0..9c70c53c72 100755 --- a/scripts/jinja_gen.py +++ b/scripts/jinja_gen.py @@ -31,10 +31,21 @@ 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") 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') + # create dictionary with useful modules etc. try: import rospkg @@ -54,7 +65,8 @@ def get_file_contents(filepath): 'gst_udp_port': args.gst_udp_port, \ 'video_uri': args.video_uri, \ 'mavlink_cam_udp_port': args.mavlink_cam_udp_port, \ - 'hil_mode': args.hil_mode} + 'hil_mode': args.hil_mode, \ + 'ros2_distro': ros2_distro} result = template.render(d)