summit hokuyo data
Hello Robotnik,
I have some question about sensor hokuyo and the data received.
I have some troubles to use the stack summit_sim in FUERTE.
I rosmaked summit_description, summit_controller inside this stack and launch the description robot:
$ roslaunch summit_description summit.launch
It looks great but in the verbose of gazebo server I have this warning:
...
...
Dbg skipping prefixed element [interface:audio] when copying plugins
Dbg skipping prefixed element [interface:audio] when copying plugins
Dbg skipping prefixed element [interface:position] when copying plugins
spawn status: SpawnModel: successfully spawned model
Dbg plugin parent sensor name: hokuyo_laser
[ WARN] [1338277432.923449936]: Laser plugin missing <hokuyoMinIntensity>, defaults to 101
[ INFO] [1338277432.923541873]: INFO: gazebo_ros_laser plugin should set minimum intensity to 101.000000 due to cutoff in hokuyo filters.
Error [Plugin.hh:100] Failed to load plugin libgazebo_ros_time.so: libgazebo_ros_time.so: cannot open shared object file: No such file or directory
Dbg plugin model name: summit
[ INFO] [1338277432.931752412]: starting gazebo_ros_controller_manager plugin in ns: /
[ INFO] [1338277432.931997347]: Callback thread id=0x7f7bc00cedf0
Gtk-Message: Failed to load module "canberra-gtk-module"
Gtk-Message: Failed to load module "canberra-gtk-module"
[spawn_object-6] process has finished cleanly
log file: /home/pablo/.ros/log/07bdad80-a962-11e1-ac58-5404a64baafd/spawn_object-6*.log
[ WARN] [1338277433.242845571]: imu plugin missing <serviceName>, defaults to /default_imu
[ WARN] [1338277433.242977926]: imu plugin missing <xyzOffset>, defaults to 0s
[ WARN] [1338277433.243170950]: imu plugin missing <rpyOffset>, defaults to 0s
[ INFO] [1338277433.328125825, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1338277433.364027285, 0.058000000]: Starting to spin physics dynamic reconfigure node...
[INFO] [WallTime: 1338277433.501923] [0.195000] Loaded controllers: summit_controller
[INFO] [WallTime: 1338277433.505892] [0.199000] Started controllers: summit_controller
Ok this is very weird because I can launch other worlds without troubles. I don't know why but I can't see the fan laser rays in the world. I can get the information of the hokuyo sensor (very bad data because it isn't logic data --> I receive only values between 0.25 and 0.05, it looks like the sensor are inside the chassis of the robot.).
If help, I put the code here:
<!-- HOKUYO SENSOR -->
<joint name="hokuyo_laser_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="0.226 0 0.125"/>
<!-- origin xyz="0.226 0 0.126"/ -->
<parent link="base_link"/>
<child link="hokuyo_laser_link"/>
</joint>
<link name="hokuyo_laser_link" type="laser">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001" />
</inertial>
</link>
<!-- This adds a visual box to allow us to see the Hokuyo in rviz/gazebo -->
<joint name="hokuyo_laser_box_joint" type="fixed">
<origin xyz="0 0 -0.02" rpy="0 0 0" /> <!-- sensor hokuyo down 2 cm -->
<parent link="hokuyo_laser_link" />
<child link="hokuyo_laser_box_link"/>
</joint>
<link name="hokuyo_laser_box_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.05 0 ...