diff --git a/camboard/manifest.xml b/camboard/manifest.xml new file mode 100644 index 0000000000000000000000000000000000000000..8b11990faea80895525a79ad69514058761e1b21 --- /dev/null +++ b/camboard/manifest.xml @@ -0,0 +1,17 @@ +<?xml version="1.0"?> + +<model> + <name>Camboard</name> + <version>1.0</version> + <sdf version="1.4">model-1_4.sdf</sdf> + <sdf version="1.5">model.sdf</sdf> + + <author> + <name>Sergi Foix</name> + <email>sfoix@iri.upc.edu</email> + </author> + + <description> + PMD camboard simulated camera. + </description> +</model> diff --git a/camboard/model-1_4.sdf b/camboard/model-1_4.sdf new file mode 100644 index 0000000000000000000000000000000000000000..e64733f8ebfc0a4b4fa967d19e048ac9a662a1c1 --- /dev/null +++ b/camboard/model-1_4.sdf @@ -0,0 +1,110 @@ +<?xml version="1.0" ?> +<sdf version="1.4"> + <model name="camboard"> + <static>false</static> + <link name="link"> + <pose>0.0 0.0 0.0 3.14 -1.57 -1.57</pose> + <inertial> + <pose>0.0 0.0 0.0 0.0 0.0 -1.57</pose> + <mass>0.2</mass> + <inertia> + <ixx>0.00009</ixx> + <iyy>0.00025</iyy> + <izz>0.00025</izz> + <ixy>0</ixy> + <ixz>0</ixz> + <iyz>0</iyz> + </inertia> + </inertial> + <collision name="collision"> + <pose>0.0 0.0 0.0 0.0 0.0 -1.57</pose> + <geometry> + <box> + <size>0.095 0.04 0.05</size> + </box> + </geometry> + <surface> + <friction> + <ode> + <mu>1.0</mu> + <mu2>1.0</mu2> + </ode> + </friction> + <contact> + <ode> + <kp>10000000.0</kp> + <kd>1.0</kd> + <min_depth>0.001</min_depth> + <max_vel>0.1</max_vel> + </ode> + </contact> + </surface> + </collision> + <visual name="visual"> + <pose>0.0 0.0 0.0 0.0 0.0 -1.57</pose> + <geometry> + <box> + <size>0.095 0.04 0.05</size> + </box> + </geometry> + </visual> + <sensor name='camera' type='depth'> + <always_on>true</always_on> + <update_rate>20</update_rate> + <visualize>false</visualize> + <camera name='__default__'> + <horizontal_fov>1.0472</horizontal_fov> + <image> + <width>200</width> + <height>200</height> + <format>L8</format> + </image> + <clip> + <near>0.01</near> + <far>7.5</far> + </clip> + <depth_camera> + <output>depths</output> + </depth_camera> + <noise> + <type>gaussian</type> + <mean>0.0</mean> + <stddev>0.0</stddev> + </noise> + </camera> + <plugin name="$camboard_controller" filename="libgazebo_ros_openni_kinect.so"> + <robotNamespace>/</robotNamespace> + <baseline>0.0</baseline> + <alwaysOn>true</alwaysOn> + <updateRate>1.0</updateRate> + <cameraName>/camboard</cameraName> + <imageTopicName>/camboard/intensity/image_raw</imageTopicName> + <cameraInfoTopicName>/camboard/intensity/camera_info</cameraInfoTopicName> + <depthImageTopicName>/camboard/depth/image_raw</depthImageTopicName> + <depthImageCameraInfoTopicName>/camboard/depth/camera_info</depthImageCameraInfoTopicName> + <pointCloudTopicName>/camboard/depth/points</pointCloudTopicName> + <frameName>tof_camera_depth_optical_frame</frameName> + <pointCloudCutoff>0.10</pointCloudCutoff> + <pointCloudCutoffMax>7.5</pointCloudCutoffMax> + <distortionK1>0.000000</distortionK1> + <distortionK2>0.000000</distortionK2> + <distortionK3>0.000000</distortionK3> + <distortionT1>0.000000</distortionT1> + <distortionT2>0.000000</distortionT2> + <CxPrime>0</CxPrime> + <Cx>0</Cx> + <Cy>0</Cy> + <focalLength>0</focalLength> + <hackBaseline>0</hackBaseline> + </plugin> + </sensor> + <velocity_decay> + <linear>0</linear> + <angular>0</angular> + </velocity_decay> + <self_collide>0</self_collide> + <kinematic>0</kinematic> + <gravity>false</gravity> + </link> + </model> +</sdf> diff --git a/camboard/model.config b/camboard/model.config new file mode 100644 index 0000000000000000000000000000000000000000..8b11990faea80895525a79ad69514058761e1b21 --- /dev/null +++ b/camboard/model.config @@ -0,0 +1,17 @@ +<?xml version="1.0"?> + +<model> + <name>Camboard</name> + <version>1.0</version> + <sdf version="1.4">model-1_4.sdf</sdf> + <sdf version="1.5">model.sdf</sdf> + + <author> + <name>Sergi Foix</name> + <email>sfoix@iri.upc.edu</email> + </author> + + <description> + PMD camboard simulated camera. + </description> +</model> diff --git a/camboard/model.sdf b/camboard/model.sdf new file mode 100644 index 0000000000000000000000000000000000000000..5bf4981d695030c69bec3fce980677198bd070a3 --- /dev/null +++ b/camboard/model.sdf @@ -0,0 +1,110 @@ +<?xml version="1.0" ?> +<sdf version="1.5"> + <model name="camboard"> + <static>false</static> + <link name="link"> + <pose>0.0 0.0 0.0 3.14 -1.57 -1.57</pose> + <inertial> + <pose>0.0 0.0 0.0 0.0 0.0 -1.57</pose> + <mass>0.2</mass> + <inertia> + <ixx>0.00009</ixx> + <iyy>0.00025</iyy> + <izz>0.00025</izz> + <ixy>0</ixy> + <ixz>0</ixz> + <iyz>0</iyz> + </inertia> + </inertial> + <collision name="collision"> + <pose>0.0 0.0 0.0 0.0 0.0 -1.57</pose> + <geometry> + <box> + <size>0.095 0.04 0.05</size> + </box> + </geometry> + <surface> + <friction> + <ode> + <mu>1.0</mu> + <mu2>1.0</mu2> + </ode> + </friction> + <contact> + <ode> + <kp>10000000.0</kp> + <kd>1.0</kd> + <min_depth>0.001</min_depth> + <max_vel>0.1</max_vel> + </ode> + </contact> + </surface> + </collision> + <visual name="visual"> + <pose>0.0 0.0 0.0 0.0 0.0 -1.57</pose> + <geometry> + <box> + <size>0.095 0.04 0.05</size> + </box> + </geometry> + </visual> + <sensor name='camera' type='depth'> + <always_on>true</always_on> + <update_rate>20</update_rate> + <visualize>false</visualize> + <camera name='__default__'> + <horizontal_fov>1.0472</horizontal_fov> + <image> + <width>200</width> + <height>200</height> + <format>L8</format> + </image> + <clip> + <near>0.01</near> + <far>7.5</far> + </clip> + <depth_camera> + <output>depths</output> + </depth_camera> + <noise> + <type>gaussian</type> + <mean>0.0</mean> + <stddev>0.0</stddev> + </noise> + </camera> + <plugin name="$camboard_controller" filename="libgazebo_ros_openni_kinect.so"> + <robotNamespace>/</robotNamespace> + <baseline>0.0</baseline> + <alwaysOn>true</alwaysOn> + <updateRate>1.0</updateRate> + <cameraName>/camboard</cameraName> + <imageTopicName>/camboard/intensity/image_raw</imageTopicName> + <cameraInfoTopicName>/camboard/intensity/camera_info</cameraInfoTopicName> + <depthImageTopicName>/camboard/depth/image_raw</depthImageTopicName> + <depthImageCameraInfoTopicName>/camboard/depth/camera_info</depthImageCameraInfoTopicName> + <pointCloudTopicName>/camboard/depth/points</pointCloudTopicName> + <frameName>tof_camera_depth_optical_frame</frameName> + <pointCloudCutoff>0.10</pointCloudCutoff> + <pointCloudCutoffMax>7.5</pointCloudCutoffMax> + <distortionK1>0.000000</distortionK1> + <distortionK2>0.000000</distortionK2> + <distortionK3>0.000000</distortionK3> + <distortionT1>0.000000</distortionT1> + <distortionT2>0.000000</distortionT2> + <CxPrime>0</CxPrime> + <Cx>0</Cx> + <Cy>0</Cy> + <focalLength>0</focalLength> + <hackBaseline>0</hackBaseline> + </plugin> + </sensor> + <velocity_decay> + <linear>0</linear> + <angular>0</angular> + </velocity_decay> + <self_collide>0</self_collide> + <kinematic>0</kinematic> + <gravity>false</gravity> + </link> + </model> +</sdf>