hi all, i'm trying to create a sensor camera on gazebo, but i have this message on the terminal when i run the launch file:
[ERROR] [1323711066.531080823]: Could not find parameter robot_description on parameter server
[ERROR] [1323711066.531205567]: Could not generate robot model
[ERROR] [1323711066.531238167]: Failed to extract kdl tree from xml robot description
[robot_state_publisher-4] process has died [pid 2161, exit code 255].
log files: /home/mauro/.ros/log/0edc0fb2-24e7-11e1-ba97-0016ea548718/robot_state_publisher-4*.log
i created a launch file:
<launch>
<node name="gazebo" pkg="gazebo" type="gazebo"
args="$(find my_erratic)/worlds/my_world.world" output="screen" respawn="false" />
<include file="$(find my_erratic)/launch/my_camera.launch" />
</launch>
the file my_camera.lauch is:
<launch>
<param name="use_sim_time" value="true" />
<!-- send the camera XML to param server -->
<param name="camera_description" command="$(find xacro)/xacro.py '$(find my_erratic)/urdf/my_camera.urdf.xacro'" />
<!-- push camera_description to factory and spawn camera in gazebo -->
<node name="spawn_robot" pkg="gazebo" type="spawn_model"
args="-param camera_description
-urdf
-x 2.5
-z 2
-P 90
-model camera_description"
respawn="false" output="screen" />
<!-- start robot state publisher -->
<node pkg="robot_state_publisher" type="state_publisher" name="robot_state_publisher" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
<param name="tf_prefix" type="string" value="" />
</node>
</launch>
the file my_camera.urdf .xacro is:
<?xml version="1.0"?>
<robot
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
<!-- Properties (Constants) -->
<property name="M_PI" value="3.14159"/>
<!-- Custom Finger Tip Camera -->
<macro name="camera">
<link name="camera_link">
<turnGravityOff>true</turnGravityOff>
<inertial>
<mass value="0.001"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0.0" ixz="0.0" iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 -0.0005" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
<joint name="finger_tip_camera_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="camera_link" />
<child link="finger_tip_camera_link"/>
</joint>
<link name="finger_tip_camera_link">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
<gazebo reference="finger_tip_camera_link">
<sensor:camera name="finger_tip_camera_sensor">
<imageSize>640 480</imageSize>
<imageFormat>R8G8B8</imageFormat>
<hfov>90</hfov>
<nearClip>0.01</nearClip>
<farClip>100</farClip>
<updateRate>20.0</updateRate>
<controller:gazebo_ros_camera name="finger_tip_camera_controller" plugin="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>20.0</updateRate>
<imageTopicName>finger_tip_cam/image</imageTopicName>
<cameraInfoTopicName>finger_tip_cam/camera_info</cameraInfoTopicName>
<frameName>finger_tip_camera_link</frameName>
<interface:camera name="finger_tip_camera_iface" />
</controller:gazebo_ros_camera>
</sensor:camera>
<turnGravityOff>true</turnGravityOff>
<material>Gazebo/Blue</material>
</gazebo>
<joint name="finger_tip_optical_joint" type="fixed">
<origin xyz="0 0 0.2" rpy="${-M_PI/2} 0.0 ${-M_PI/2}" />
<parent link="finger_tip_camera_link" />
<child link="finger_tip_optical_frame"/>
</joint>
<link name="finger_tip_optical_frame">
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</collision>
</link>
<gazebo reference="camera_link">
<material>Erratic/Yellow</material>
</gazebo>
<gazebo reference="finger_tip_camera_link">
<material>Erratic/Yellow</material>
</gazebo>
<gazebo reference="finger_tip_optical_frame">
<material>Erratic/Yellow</material>
</gazebo>
</macro>
</robot>
Originally posted by Maurizio88 on ROS Answers with karma: 155 on 2011-12-12
Post score: 0