what are the intesity values from gazebo-ros-laser plugin
The gazebo_ros_laser plugin sends sensor_msgs/LaserScan
messages, that contain list of floats called intensities
.
sensor_msgs/LaserScan
:
std_msgs/Header header
uint32 seq
time stamp
string frame_id
float32 angle_min
float32 angle_max
float32 angle_increment
float32 time_increment
float32 scan_time
float32 range_min
float32 range_max
float32[] ranges
float32[] intensities
Inside the the gazebo_ros_laser plugin source file, the list is being filled with following code.
std::copy(_msg->scan().intensities().begin(),
_msg->scan().intensities().end(),
laser_msg.intensities.begin());
I understand the ranges
list contains the distance to closest obstacle intercepted by the ray, but what does physically the intensity values represent?