ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

how to use the hokuyo plugin in gazebo

asked 2012-10-27 00:21:51 -0500

BaBs gravatar image

updated 2014-01-28 17:14:05 -0500

ngrennan gravatar image

Hello,

For a first test I want to use the gazebo plugin for the Hokuyo node, ( I later want to attach it to a Husky), when I run

$rosrun gazebo_plugins hokuyo_node

The plugin starts and in the terminal appears "starting to spin" but there is no model in gazebo and moreover there are no scan messages published ( which I need for rviz etc).

How can I use the plugin so I can get scan messages ?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2012-10-27 03:14:17 -0500

cagatay gravatar image

updated 2012-10-27 03:14:47 -0500

Hello, you should have a laser link which represents the origin of your laser hardware attached to base_link or etc.. in your model such as in turtlebot 's urdf

    <joint name="laser_joint" type="fixed">
    <origin xyz="-0.065 0 0.075" rpy="0 0 0" />
    <parent link="base_link" />
    <child link="laser" />
  </joint>

<link name="laser"> <visual> <geometry> <box size="0.02 0.035 0.002"/> </geometry> <material name="Green"/> </visual> <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> </link>

then in order to use this laser scanner in gazebo you should add laser scanner plugin

    <xacro:macro name="turtlebot_sim_laser">
  <gazebo reference="laser">
    <sensor:ray name="laser">
      <rayCount>180</rayCount>
      <rangeCount>180</rangeCount>
      <laserCount>1</laserCount>

      <origin>0.0 0.0 0.0</origin>
      <displayRays>false</displayRays>

      <minAngle>-130</minAngle>
      <maxAngle>130</maxAngle>

      <minRange>0.08</minRange>
      <maxRange>10.0</maxRange>
      <resRange>0.01</resRange>
      <updateRate>20</updateRate>
      <controller:gazebo_ros_laser name="gazebo_ros_laser_controller" plugin="libgazebo_ros_laser.so">
    <gaussianNoise>0.005</gaussianNoise>
    <alwaysOn>true</alwaysOn>
    <updateRate>20</updateRate>
    <topicName>scan</topicName>
    <frameName>laser</frameName>
    <interface:laser name="gazebo_ros_laser_iface" />
      </controller:gazebo_ros_laser>
    </sensor:ray>
  </gazebo>
</xacro:macro>
edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-10-27 00:21:51 -0500

Seen: 8,378 times

Last updated: Oct 27 '12