Skip to content
Snippets Groups Projects
Commit 9b452b54 authored by marvin's avatar marvin
Browse files

Add sensorconfigs

parent 3cd5f62a
1 merge request!6Adapter custombot
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<featureModel>
<properties>
<graphics key="showhiddenfeatures" value="true"/>
<graphics key="legendautolayout" value="true"/>
<graphics key="showshortnames" value="false"/>
<graphics key="layout" value="horizontal"/>
<graphics key="showcollapsedconstraints" value="true"/>
<graphics key="legendhidden" value="false"/>
<graphics key="layoutalgorithm" value="1"/>
</properties>
<struct>
<and abstract="true" mandatory="true" name="CarConfigurator">
<and mandatory="true" name="ConfiguratorMain">
<and abstract="true" mandatory="true" name="TurtleBot">
<alt abstract="true" mandatory="true" name="Templates">
<graphics key="collapsed" value="false"/>
<feature name="Burger"/>
<feature name="Waffle"/>
<feature name="WafflePi"/>
</alt>
<alt abstract="true" mandatory="true" name="Sensors">
<feature name="NO_CHANGE"/>
<and abstract="true" name="Custom">
<feature name="imu"/>
<feature name="lds_lfcd_sensor"/>
<feature name="Pi_Camera"/>
<feature name="realsense_R200"/>
</and>
</alt>
</and>
</and>
</and>
</struct>
</featureModel>
<?xml version="1.0"?>
<configuration>
<gazebo reference="camera_rgb_frame">
<sensor type="camera" name="Pi Camera">
<always_on>true</always_on>
<visualize>$(arg camera_visual)</visualize>
<camera>
<horizontal_fov>1.085595</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.03</near>
<far>100</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>camera</cameraName>
<frameName>camera_rgb_optical_frame</frameName>
<imageTopicName>image</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
</configuration>
<?xml version="1.0"?>
<configuration>
<gazebo reference="imu_link">
<sensor type="imu" name="imu">
<always_on>true</always_on>
<visualize>$(arg imu_visual)</visualize>
</sensor>
<material>Gazebo/FlatBlack</material>
</gazebo>
</configuration>
<?xml version="1.0"?>
<configuration>
<gazebo reference="base_scan">
<material>Gazebo/FlatBlack</material>
<sensor type="ray" name="lds_lfcd_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>$(arg laser_visual)</visualize>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>0.0</min_angle>
<max_angle>6.28319</max_angle>
</horizontal>
</scan>
<range>
<min>0.120</min>
<max>3.5</max>
<resolution>0.015</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_lds_lfcd_controller" filename="libgazebo_ros_laser.so">
<topicName>scan</topicName>
<frameName>base_scan</frameName>
</plugin>
</sensor>
</gazebo>
</configuration>
<?xml version="1.0"?>
<configuration>
<gazebo reference="camera_rgb_frame">
<sensor type="depth" name="realsense_R200">
<always_on>true</always_on>
<visualize>$(arg camera_visual)</visualize>
<camera>
<horizontal_fov>1.3439</horizontal_fov>
<image>
<width>1920</width>
<height>1080</height>
<format>R8G8B8</format>
</image>
<depth_camera></depth_camera>
<clip>
<near>0.03</near>
<far>100</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<cameraName>camera</cameraName>
<frameName>camera_rgb_optical_frame</frameName>
<imageTopicName>rgb/image_raw</imageTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudCutoff>0.4</pointCloudCutoff>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
<CxPrime>0.0</CxPrime>
<Cx>0.0</Cx>
<Cy>0.0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
</configuration>
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment