In order to spawn a laser sensor in Gazebo and visualize the laser scan in Rviz there are some steps missing. For instance:
You need an URDF file, this is a minimal example (lets call it laser_sensor.urdf):
<?xml version="1.0"?>
<robot name="cube_laser">
<link name="base_link">
<visual>
<geometry>
<box size="0.2 0.2 0.2"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.2 0.2 0.2"/>
</geometry>
</collision>
</link>
<!-- a cube to use as laser sensor geometry -->
<link name="hokuyo_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<joint name="hokuyo_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="hokuyo_link"/>
</joint>
<!-- placeholder for laser sensor plugin-->
</robot>
You have to add the following Gazebo tag with a plugin that interacts with ROS (put it where the placeholder is):
<!-- this is a laser sensor-->
<gazebo reference="hokuyo_link">
<sensor type="ray" name="laser">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="gazebo_ros_laser" filename="libgazebo_ros_laser.so">
<topicName>laser/scan</topicName>
<frameName>hokuyo_link</frameName>
</plugin>
</sensor>
</gazebo>
<frameName>
must match the name of one link in the URDF file.
Fire up Gazebo:
$ roslaunch gazebo_ros empty_world.launch
Then cd
to where you saved your URDF file.
Next spawn the URDF model to Gazebo:
$ rosrun gazebo_ros spawn_model -file laser_sensor.urdf -urdf -z 0.5 -model laser_sensor
Load the robot model to parameter server:
$ rosparam set robot_description --textfile laser_sensor.urdf
To broadcast the robot model (from the URDF description) to the tf transform library run:
$ rosrun joint_state_publisher joint_state_publisher
$ rosrun robot_state_publisher robot_state_publisher
To verify that everything in running:
$ rostopic list
$ rostopic echo tf_static
Then open Rviz.
Select the drop_down for fixed frame and type in "base_link".
Finally add a LaserScan visualization and set the correct topic.
I can recommend starting with these tutorials:
Building a Visual Robot Model with URDF from Scratch
http://wiki.ros.org/urdf/Tutorials/Bu...
Tutorial: Using Gazebo plugins with ROS
http://gazebosim.org/tutorials?tut=ro...
Rviz is a ROS tool and Gazebo does not require ROS to run and does not natively publish ros topics and ros TF's. So you need an interface for using ROS with Gazebo. Following just the steps mentioned above does not provide a rostopic. Running roscore and then rviz just provides these ros topics: /clicked_point /initialpose /move_base_simple/goal /rosout /rosout_agg /tf /tf_static But if you do have a rostopic showing up a laser msg, as you mention, you should also have an URDF model with a plugin definition on it? Could you confirm?
The included hokuyo model does use a laser plugin.
This is in the sdf of the hokuyo laser. As u can see the frameName is set to map but there is no tf topic being published. You are right that gazebo doesn't require ros to run, but see that I am not opening gazebo from my app drawer, I am opening it with the launch file which will bind gazebo to ros.