diff --git a/launch/iri_lidar_lite.launch b/launch/iri_lidar_lite.launch index 3408a7b040791c565168667f3378a38e542dc28b..0f9e15fe764951cbac725e3c10647033108b9c3b 100644 --- a/launch/iri_lidar_lite.launch +++ b/launch/iri_lidar_lite.launch @@ -6,6 +6,7 @@ <param name="serial_num" type="string" value="A700evSl"/> <param name="config_mode" type="int" value="1"/> <param name="frame_id" type="string" value="/kinton/lidarlite_link"/> + <remap from="~range" to="kinton/lidarlite_range"/> </node> </launch> diff --git a/src/lidar_lite_driver_node.cpp b/src/lidar_lite_driver_node.cpp index 79ef6b4ef01feb75d375df49b537d7092d65bccc..25ba4e3b525c5e70b07c5ae7a4805cfef7c016ff 100644 --- a/src/lidar_lite_driver_node.cpp +++ b/src/lidar_lite_driver_node.cpp @@ -54,7 +54,7 @@ LidarLiteDriverNode::ThreadFunc(void) this->range_msg_.field_of_view = 0.1; this->range_msg_.min_range = 0; this->range_msg_.max_range = 40; - this->range_msg_.range = range; + this->range_msg_.range = range/100.0; this->range_publisher_.publish(this->range_msg_); // Increment range publisher counter.