diff --git a/.rosinstall b/.rosinstall
deleted file mode 100644
index aca588c..0000000
--- a/.rosinstall
+++ /dev/null
@@ -1,2 +0,0 @@
-- git: { local-name: AndreaCensi/csm, uri: 'https://github.com/AndreaCensi/csm.git', version: master } ## Needed for building laser_scan_matcher
-- git: { local-name: ccny-ros-pkg/scan_tools, uri: 'https://github.com/ccny-ros-pkg/scan_tools.git', version: indigo }
diff --git a/laser_scan_splitter/src/laser_scan_splitter_node.cpp b/LICENSE
similarity index 84%
rename from laser_scan_splitter/src/laser_scan_splitter_node.cpp
rename to LICENSE
index e62d0b4..84eaee7 100644
--- a/laser_scan_splitter/src/laser_scan_splitter_node.cpp
+++ b/LICENSE
@@ -25,16 +25,4 @@
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_scan_splitter/laser_scan_splitter.h"
-
-int main (int argc, char **argv)
-{
- ros::init (argc, argv, "LaserScanSplitter");
- ros::NodeHandle nh;
- ros::NodeHandle nh_private("~");
- scan_tools::LaserScanSplitter laser_scan_splitter(nh, nh_private);
- ros::spin ();
- return 0;
-}
+ */
\ No newline at end of file
diff --git a/README.md b/README.md
index 2cb50d3..33c8227 100644
--- a/README.md
+++ b/README.md
@@ -6,54 +6,18 @@ Overview
Laser scan processing tools. The meta-package contains:
- * `laser_ortho_projector`: calculates orthogonal projections of LaserScan messages
-
* `laser_scan_matcher`: an incremental laser scan matcher, using Andrea Censi's Canonical
-Scan Matcher implementation. It downloads and installs Andrea Censi's Canonical Scan Matcher [1] locally.
-
- * `laser_scan_sparsifier`: takes in a LaserScan message and sparsifies it
-
- * `laser_scan_splitter`: takes in a LaserScan message and splits
-it into a number of other LaserScan messages
-
- * `ncd_parser`: reads in .alog data files from the New College Dataset [2]
-and broadcasts scan and odometry messages to ROS.
+Scan Matcher [1] implementation.
* `scan_to_cloud_converter`: converts LaserScan to PointCloud messages.
-Installing
+License
-----------------------------------
-### Prerequisite
-
-* ROS is installed
- * [1-liner ROS Indigo installation on Ubuntu](http://wiki.ros.org/ROS/Installation/TwoLineInstall)
-* `apt-get install python-wstool`
-
-### From binary (RECOMMENDED)
-
-```
-apt-get install ros-%ROS_DISTRO%-scan-tools
-
-apt-get install ros-indigo-scan-tools (Indigo)
-```
-
-### From source ###
-
-Following is an example with ROS Indigo.
-
-1. Create a [catkin workspace](http://wiki.ros.org/catkin/Tutorials/create_a_workspace) and navigate to its source directory (e.g. `~/catkin_ws/src`).
-
-2. In your Catkin workspace, download source and build with the following commands.
+This repo is licensed with [BSD-3-Clause](https://opensource.org/licenses/BSD-3-Clause), but depends on the version
+of [CSM](https://github.com/AndreaCensi/csm) which uses [eigen](https://eigen.tuxfamily.org/). CSM itself
+is [LGPL-3.0](https://opensource.org/licenses/LGPL-3.0), while eigen is [MPL-2.0](https://opensource.org/licenses/MPL-2.0)
-```
-cd ~/catkin_ws
-wstool init src
-wstool merge -t src https://raw.githubusercontent.com/ccny-ros-pkg/scan_tools/indigo/.rosinstall
-rosdep install --from-paths src --ignore-src --rosdistro indigo -r -y
-catkin_make (or any build commands available in ROS, e.g. `catkin build`)
-source devel/setup.bash
-```
More info
-----------------------------------
diff --git a/laser_ortho_projector/.gitignore b/laser_ortho_projector/.gitignore
deleted file mode 100644
index bad425f..0000000
--- a/laser_ortho_projector/.gitignore
+++ /dev/null
@@ -1,2 +0,0 @@
-msg_gen/
-build/
diff --git a/laser_ortho_projector/CHANGELOG.rst b/laser_ortho_projector/CHANGELOG.rst
deleted file mode 100644
index 40000bb..0000000
--- a/laser_ortho_projector/CHANGELOG.rst
+++ /dev/null
@@ -1,23 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package laser_ortho_projector
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-
-0.3.3 (2021-02-15)
-------------------
-* [maintenance] update to use non deprecated pluginlib macro
-
-0.3.2 (2016-03-19)
-------------------
-
-0.3.1 (2015-12-18)
-------------------
-
-0.3.0 (2015-11-10)
-------------------
-
-0.2.1 (2015-10-14)
-------------------
-* [feat] added support for IMU message for orientation in laser_ortho_projector. The imu topic is imu/data
-* [fix] PCL dependency Hydro onward
-* [sys] Catkinization: laser_ortho_projector
-* Contributors: Ivan Dryanovski, Miguel Sarabia, Enrique Fernández Perdomo
diff --git a/laser_ortho_projector/CMakeLists.txt b/laser_ortho_projector/CMakeLists.txt
deleted file mode 100644
index 160a84a..0000000
--- a/laser_ortho_projector/CMakeLists.txt
+++ /dev/null
@@ -1,63 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(laser_ortho_projector)
-
-# List C++ dependencies on ros packages
-set( ROS_CXX_DEPENDENCIES
- roscpp
- nodelet
- sensor_msgs
- tf
- pcl_ros
- pcl_conversions
- geometry_msgs
- message_filters)
-
-# Find catkin and all required ROS components
-find_package(catkin REQUIRED COMPONENTS ${ROS_CXX_DEPENDENCIES})
-find_package(PCL REQUIRED QUIET)
-
-# Set include directories
-include_directories(include ${catkin_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
-
-# Declare info that other packages need to import library generated here
-catkin_package(
- INCLUDE_DIRS include
- LIBRARIES laser_ortho_projector
- CATKIN_DEPENDS ${ROS_CXX_DEPENDENCIES} )
-
-#Create library
-add_library(laser_ortho_projector src/laser_ortho_projector.cpp)
-
-#Note we don't link against pcl as we're using header-only parts of the library
-target_link_libraries( laser_ortho_projector ${catkin_LIBRARIES})
-add_dependencies(laser_ortho_projector ${catkin_EXPORTED_TARGETS})
-
-#Create nodelet
-add_library(laser_ortho_projector_nodelet src/laser_ortho_projector_nodelet.cpp)
-target_link_libraries(laser_ortho_projector_nodelet laser_ortho_projector)
-
-#Create node
-add_executable(laser_ortho_projector_node src/laser_ortho_projector_node.cpp)
-target_link_libraries( laser_ortho_projector_node laser_ortho_projector )
-
-#Install library
-install(TARGETS laser_ortho_projector laser_ortho_projector_nodelet
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
-
-#Install library includes
-install(DIRECTORY include/laser_ortho_projector/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} )
-
-#Install node
-install(TARGETS laser_ortho_projector_node
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} )
-
-#Install nodelet description
-install(FILES laser_ortho_projector_nodelet.xml
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
-
-#Install demo files
-install(DIRECTORY demo
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
diff --git a/laser_ortho_projector/demo/demo.bag b/laser_ortho_projector/demo/demo.bag
deleted file mode 100644
index 9f753c1..0000000
Binary files a/laser_ortho_projector/demo/demo.bag and /dev/null differ
diff --git a/laser_ortho_projector/demo/demo.launch b/laser_ortho_projector/demo/demo.launch
deleted file mode 100644
index 4f2d17b..0000000
--- a/laser_ortho_projector/demo/demo.launch
+++ /dev/null
@@ -1,22 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/laser_ortho_projector/demo/demo.vcg b/laser_ortho_projector/demo/demo.vcg
deleted file mode 100644
index a49cc9b..0000000
--- a/laser_ortho_projector/demo/demo.vcg
+++ /dev/null
@@ -1,105 +0,0 @@
-Background\ ColorR=0
-Background\ ColorG=0
-Background\ ColorB=0
-Fixed\ Frame=/world
-Target\ Frame=
-Grid.Alpha=0.5
-Grid.Cell\ Size=1
-Grid.ColorR=0.5
-Grid.ColorG=0.5
-Grid.ColorB=0.5
-Grid.Enabled=1
-Grid.Line\ Style=0
-Grid.Line\ Width=0.03
-Grid.Normal\ Cell\ Count=0
-Grid.OffsetX=0
-Grid.OffsetY=0
-Grid.OffsetZ=0
-Grid.Plane=0
-Grid.Plane\ Cell\ Count=10
-Grid.Reference\ Frame=
-Laser\ Scan.Alpha=1
-Laser\ Scan.Billboard\ Size=0.01
-Laser\ Scan.Color\ Transformer=Flat Color
-Laser\ Scan.Decay\ Time=0
-Laser\ Scan.Enabled=1
-Laser\ Scan.Position\ Transformer=XYZ
-Laser\ Scan.Selectable=1
-Laser\ Scan.Style=0
-Laser\ Scan.Topic=/scan
-Laser\ Scan..AxisAutocompute\ Value\ Bounds=1
-Laser\ Scan..AxisAxis=2
-Laser\ Scan..AxisMax\ Value=10
-Laser\ Scan..AxisMin\ Value=-10
-Laser\ Scan..AxisUse\ Fixed\ Frame=1
-Laser\ Scan..Flat\ ColorColorR=1
-Laser\ Scan..Flat\ ColorColorG=0
-Laser\ Scan..Flat\ ColorColorB=0
-Laser\ Scan..IntensityAutocompute\ Intensity\ Bounds=1
-Laser\ Scan..IntensityMax\ ColorR=1
-Laser\ Scan..IntensityMax\ ColorG=1
-Laser\ Scan..IntensityMax\ ColorB=1
-Laser\ Scan..IntensityMax\ Intensity=4096
-Laser\ Scan..IntensityMin\ ColorR=0
-Laser\ Scan..IntensityMin\ ColorG=0
-Laser\ Scan..IntensityMin\ ColorB=0
-Laser\ Scan..IntensityMin\ Intensity=0
-Projected\ Scan.Alpha=1
-Projected\ Scan.Billboard\ Size=0.01
-Projected\ Scan.Color\ Transformer=Flat Color
-Projected\ Scan.Decay\ Time=0
-Projected\ Scan.Enabled=1
-Projected\ Scan.Position\ Transformer=XYZ
-Projected\ Scan.Selectable=1
-Projected\ Scan.Style=0
-Projected\ Scan.Topic=/cloud_ortho
-Projected\ Scan..AxisAutocompute\ Value\ Bounds=1
-Projected\ Scan..AxisAxis=2
-Projected\ Scan..AxisMax\ Value=9.30076e-08
-Projected\ Scan..AxisMin\ Value=-4.3073e-08
-Projected\ Scan..AxisUse\ Fixed\ Frame=1
-Projected\ Scan..Flat\ ColorColorR=0.00392157
-Projected\ Scan..Flat\ ColorColorG=1
-Projected\ Scan..Flat\ ColorColorB=0
-Projected\ Scan..IntensityAutocompute\ Intensity\ Bounds=1
-Projected\ Scan..IntensityMax\ ColorR=1
-Projected\ Scan..IntensityMax\ ColorG=1
-Projected\ Scan..IntensityMax\ ColorB=1
-Projected\ Scan..IntensityMax\ Intensity=4096
-Projected\ Scan..IntensityMin\ ColorR=0
-Projected\ Scan..IntensityMin\ ColorG=0
-Projected\ Scan..IntensityMin\ ColorB=0
-Projected\ Scan..IntensityMin\ Intensity=0
-TF.All\ Enabled=1
-TF.Enabled=1
-TF.Frame\ Timeout=15
-TF.Show\ Arrows=1
-TF.Show\ Axes=1
-TF.Show\ Names=1
-TF.Update\ Interval=0
-Tool\ 2D\ Nav\ GoalTopic=goal
-Tool\ 2D\ Pose\ EstimateTopic=initialpose
-Camera\ Type=rviz::OrbitViewController
-Camera\ Config=1.32755 0.285803 10.4633 -0.797791 1.83787 -1.22537
-Property\ Grid\ State=selection=;expanded=.Global Options,TF./base_link/base_link,TF./laser/laser,TF./world/world,TF./base_ortho/base_ortho,TF.Enabled.TF.Tree,TF./worldTree/world,TF./base_linkTree/base_link,TF./laserTree/laser,TF./base_orthoTree/base_ortho;scrollpos=0,0;splitterpos=139,279;ispageselected=1
-[Display0]
-Name=TF
-Package=rviz
-ClassName=rviz::TFDisplay
-[Display1]
-Name=Laser Scan
-Package=rviz
-ClassName=rviz::LaserScanDisplay
-[Display2]
-Name=Grid
-Package=rviz
-ClassName=rviz::GridDisplay
-[Display3]
-Name=Projected Scan
-Package=rviz
-ClassName=rviz::PointCloud2Display
-[TF.]
-base_linkEnabled=1
-base_orthoEnabled=1
-laserEnabled=1
-worldEnabled=1
diff --git a/laser_ortho_projector/include/laser_ortho_projector/laser_ortho_projector.h b/laser_ortho_projector/include/laser_ortho_projector/laser_ortho_projector.h
deleted file mode 100644
index ba5e7fd..0000000
--- a/laser_ortho_projector/include/laser_ortho_projector/laser_ortho_projector.h
+++ /dev/null
@@ -1,114 +0,0 @@
-/*
- * Copyright (c) 2010, 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_H
-#define LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_H
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-namespace scan_tools {
-
-class LaserOrthoProjector
-{
- typedef pcl::PointXYZ PointT;
- typedef pcl::PointCloud PointCloudT;
-
- typedef geometry_msgs::PoseStamped PoseMsg;
- typedef sensor_msgs::Imu ImuMsg;
-
- public:
-
- LaserOrthoProjector (ros::NodeHandle nh, ros::NodeHandle nh_private);
- virtual ~ LaserOrthoProjector ();
-
- private:
-
- // **** ROS-related
-
- ros::NodeHandle nh_;
- ros::NodeHandle nh_private_;
-
- ros::Publisher cloud_publisher_;
-
- ros::Subscriber scan_subscriber_;
- ros::Subscriber imu_subscriber_;
- ros::Subscriber pose_subscriber_;
-
- tf::TransformListener tf_listener_;
- tf::TransformBroadcaster tf_broadcaster_;
-
- // **** paramaters
-
- std::string world_frame_;
- std::string base_frame_;
- std::string ortho_frame_;
-
- bool publish_tf_;
- bool use_pose_;
- bool use_imu_;
-
- // **** state variables
-
- bool initialized_;
-
- std::vector a_sin_;
- std::vector a_cos_;
-
- PointT nan_point_;
-
- tf::Transform base_to_laser_; // static, cached
- tf::Transform ortho_to_laser_; // computed from b2l, w2b, w2o
-
- void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
- void poseCallback (const PoseMsg::ConstPtr& pose_msg);
- void imuCallback (const ImuMsg::ConstPtr& imu_msg);
- void getOrthoTf(const tf::Transform& world_to_base, tf::Transform& world_to_ortho);
- bool getBaseToLaserTf (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
- void createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
-
-
-};
-
-} // namespace scan_tools
-
-#endif // LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_H
diff --git a/laser_ortho_projector/include/laser_ortho_projector/laser_ortho_projector_nodelet.h b/laser_ortho_projector/include/laser_ortho_projector/laser_ortho_projector_nodelet.h
deleted file mode 100644
index cfc714f..0000000
--- a/laser_ortho_projector/include/laser_ortho_projector/laser_ortho_projector_nodelet.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- * Copyright (c) 2010, 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_NODELET_H
-#define LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_NODELET_H
-
-#include
-#include
-
-#include "laser_ortho_projector/laser_ortho_projector.h"
-
-namespace scan_tools {
-
-class LaserOrthoProjectorNodelet : public nodelet::Nodelet
-{
- public:
- virtual void onInit();
-
- private:
- LaserOrthoProjector * laser_ortho_projector_; // FIXME: change to smart pointer
-};
-
-} //namespace scan tools
-
-#endif // LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_NODELET_H
diff --git a/laser_ortho_projector/laser_ortho_projector_nodelet.xml b/laser_ortho_projector/laser_ortho_projector_nodelet.xml
deleted file mode 100644
index ea6bd53..0000000
--- a/laser_ortho_projector/laser_ortho_projector_nodelet.xml
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
-
- Laser ortho projector nodelet publisher.
-
-
-
diff --git a/laser_ortho_projector/package.xml b/laser_ortho_projector/package.xml
deleted file mode 100644
index 47bbab9..0000000
--- a/laser_ortho_projector/package.xml
+++ /dev/null
@@ -1,44 +0,0 @@
-
- laser_ortho_projector
- 0.3.3
-
- The laser_ortho_projector package calculates orthogonal projections of LaserScan messages.
-
- Ivan Dryanovski
- Carlos
-
- http://wiki.ros.org/laser_scan_matcher
- Ivan Dryanovski
- William Morris
-
- BSD
-
- catkin
-
- roscpp
- nodelet
- sensor_msgs
- tf
- pcl_ros
- pcl_conversions
- geometry_msgs
- message_filters
-
- libpcl-all-dev
-
- roscpp
- nodelet
- sensor_msgs
- tf
- pcl_ros
- pcl_conversions
- geometry_msgs
- message_filters
-
- libpcl-all
-
-
-
-
-
-
diff --git a/laser_ortho_projector/src/laser_ortho_projector.cpp b/laser_ortho_projector/src/laser_ortho_projector.cpp
deleted file mode 100644
index c5bdc45..0000000
--- a/laser_ortho_projector/src/laser_ortho_projector.cpp
+++ /dev/null
@@ -1,256 +0,0 @@
-/*
- * Copyright (c) 2010, 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_ortho_projector/laser_ortho_projector.h"
-
-#include
-
-namespace scan_tools {
-
-LaserOrthoProjector::LaserOrthoProjector (ros::NodeHandle nh, ros::NodeHandle nh_private):
- nh_(nh),
- nh_private_(nh_private)
-{
- ROS_INFO ("Starting LaserOrthoProjector");
-
- initialized_ = false;
-
- // set initial orientation to 0
-
- ortho_to_laser_.setIdentity();
-
- nan_point_.x = std::numeric_limits::quiet_NaN();
- nan_point_.y = std::numeric_limits::quiet_NaN();
- nan_point_.z = std::numeric_limits::quiet_NaN();
-
- // **** parameters
-
- if (!nh_private_.getParam ("fixed_frame", world_frame_))
- world_frame_ = "/world";
- if (!nh_private_.getParam ("base_frame", base_frame_))
- base_frame_ = "/base_link";
- if (!nh_private_.getParam ("ortho_frame", ortho_frame_))
- ortho_frame_ = "/base_ortho";
- if (!nh_private_.getParam ("publish_tf", publish_tf_))
- publish_tf_ = false;
- if (!nh_private_.getParam ("use_pose", use_pose_))
- use_pose_ = true;
- if (!nh_private_.getParam ("use_imu", use_imu_))
- use_imu_ = false;
-
- if (use_imu_ && use_pose_)
- ROS_FATAL("use_imu and use_pose params cannot both be true");
- if (!use_imu_ && !use_pose_)
- ROS_FATAL("use_imu and use_pose params cannot both be false");
-
-
- // **** subscribe to laser scan messages
-
- scan_subscriber_ = nh_.subscribe(
- "scan", 10, &LaserOrthoProjector::scanCallback, this);
-
- if (use_pose_)
- {
- pose_subscriber_ = nh_.subscribe(
- "pose", 10, &LaserOrthoProjector::poseCallback, this);
- }
- if (use_imu_)
- {
- imu_subscriber_ = nh_.subscribe(
- "imu/data", 10, &LaserOrthoProjector::imuCallback, this);
- }
-
- // **** advertise orthogonal scan
-
- cloud_publisher_ = nh_.advertise(
- "cloud_ortho", 10);
-}
-
-LaserOrthoProjector::~LaserOrthoProjector()
-{
-
-}
-
-void LaserOrthoProjector::imuCallback(const ImuMsg::ConstPtr& imu_msg)
-{
- // obtain world to base frame transform from the pose message
- tf::Transform world_to_base;
- world_to_base.setIdentity();
-
- tf::Quaternion q;
- tf::quaternionMsgToTF(imu_msg->orientation, q);
- world_to_base.setRotation(q);
-
- // calculate world to ortho frame transform
- tf::Transform world_to_ortho;
- getOrthoTf(world_to_base, world_to_ortho);
-
- if (publish_tf_)
- {
- tf::StampedTransform world_to_ortho_tf(
- world_to_ortho, imu_msg->header.stamp, world_frame_, ortho_frame_);
- tf_broadcaster_.sendTransform(world_to_ortho_tf);
- }
-
- // calculate ortho to laser tf, and save it for when scans arrive
- ortho_to_laser_ = world_to_ortho.inverse() * world_to_base * base_to_laser_;
-}
-
-void LaserOrthoProjector::poseCallback(const PoseMsg::ConstPtr& pose_msg)
-{
- // obtain world to base frame transform from the pose message
- tf::Transform world_to_base;
- tf::poseMsgToTF(pose_msg->pose, world_to_base);
-
- // calculate world to ortho frame transform
- tf::Transform world_to_ortho;
- getOrthoTf(world_to_base, world_to_ortho);
-
- if (publish_tf_)
- {
- tf::StampedTransform world_to_ortho_tf(
- world_to_ortho, pose_msg->header.stamp, world_frame_, ortho_frame_);
- tf_broadcaster_.sendTransform(world_to_ortho_tf);
- }
-
- // calculate ortho to laser tf, and save it for when scans arrive
- ortho_to_laser_ = world_to_ortho.inverse() * world_to_base * base_to_laser_;
-}
-
-void LaserOrthoProjector::getOrthoTf(const tf::Transform& world_to_base, tf::Transform& world_to_ortho)
-{
- const tf::Vector3& w2b_o = world_to_base.getOrigin();
- const tf::Quaternion& w2b_q = world_to_base.getRotation();
-
- tf::Vector3 wto_o(w2b_o.getX(), w2b_o.getY(), 0.0);
- tf::Quaternion wto_q = tf::createQuaternionFromYaw(tf::getYaw(w2b_q));
-
- world_to_ortho.setOrigin(wto_o);
- world_to_ortho.setRotation(wto_q);
-}
-
-void LaserOrthoProjector::scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan_msg)
-{
- if(!initialized_)
- {
- initialized_ = getBaseToLaserTf(scan_msg);
-
- if (initialized_) createCache(scan_msg);
- else return;
- }
-
- if(!use_pose_)
- {
- // obtain transform between fixed and base frame
- tf::StampedTransform world_to_base_tf;
- try
- {
- tf_listener_.waitForTransform (
- world_frame_, base_frame_, scan_msg->header.stamp, ros::Duration(0.1));
- tf_listener_.lookupTransform (
- world_frame_, base_frame_, scan_msg->header.stamp, world_to_base_tf);
- }
- catch (tf::TransformException ex)
- {
- // transform unavailable - skip scan
- ROS_WARN("Skipping scan %s", ex.what());
- return;
- }
-
- // calculate world to ortho frame transform
- tf::Transform world_to_ortho;
- getOrthoTf(world_to_base_tf, world_to_ortho);
- }
-
- // **** build and publish projected cloud
-
- PointCloudT::Ptr cloud =
- boost::shared_ptr(new PointCloudT());
-
- pcl_conversions::toPCL(scan_msg->header, cloud->header);
- cloud->header.frame_id = ortho_frame_;
-
- for (unsigned int i = 0; i < scan_msg->ranges.size(); i++)
- {
- double r = scan_msg->ranges[i];
-
- if (r > scan_msg->range_min)
- {
- tf::Vector3 p(r * a_cos_[i], r * a_sin_[i], 0.0);
- p = ortho_to_laser_ * p;
-
- PointT point;
- point.x = p.getX();
- point.y = p.getY();
- point.z = 0.0;
- cloud->points.push_back(point);
- }
- }
-
- cloud->width = cloud->points.size();
- cloud->height = 1;
- cloud->is_dense = true; // no nan's present
-
- cloud_publisher_.publish (cloud);
-}
-
-bool LaserOrthoProjector::getBaseToLaserTf (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
-{
- tf::StampedTransform base_to_laser_tf;
- try
- {
- tf_listener_.waitForTransform(
- base_frame_, scan_msg->header.frame_id, scan_msg->header.stamp, ros::Duration(1.0));
- tf_listener_.lookupTransform (
- base_frame_, scan_msg->header.frame_id, scan_msg->header.stamp, base_to_laser_tf);
- }
- catch (tf::TransformException ex)
- {
- ROS_WARN("LaserOrthoProjector: Could not get initial laser transform(%s)", ex.what());
- return false;
- }
- base_to_laser_ = base_to_laser_tf;
-
- return true;
-}
-
-void LaserOrthoProjector::createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
-{
- a_cos_.clear();
- a_sin_.clear();
-
- for (unsigned int i = 0; i < scan_msg->ranges.size(); ++i)
- {
- double angle = scan_msg->angle_min + i * scan_msg->angle_increment;
- a_cos_.push_back(cos(angle));
- a_sin_.push_back(sin(angle));
- }
-}
-
-} //namespace scan_tools
diff --git a/laser_ortho_projector/src/laser_ortho_projector_node.cpp b/laser_ortho_projector/src/laser_ortho_projector_node.cpp
deleted file mode 100644
index 88f8a77..0000000
--- a/laser_ortho_projector/src/laser_ortho_projector_node.cpp
+++ /dev/null
@@ -1,40 +0,0 @@
-/*
- * Copyright (c) 2010, 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_ortho_projector/laser_ortho_projector.h"
-
-int main (int argc, char **argv)
-{
- ros::init (argc, argv, "LaserOrthoProjector");
- ros::NodeHandle nh;
- ros::NodeHandle nh_private("~");
- scan_tools::LaserOrthoProjector laser_ortho_projector(nh, nh_private);
- ros::spin ();
- return 0;
-}
diff --git a/laser_ortho_projector/src/laser_ortho_projector_nodelet.cpp b/laser_ortho_projector/src/laser_ortho_projector_nodelet.cpp
deleted file mode 100644
index a1f04a3..0000000
--- a/laser_ortho_projector/src/laser_ortho_projector_nodelet.cpp
+++ /dev/null
@@ -1,45 +0,0 @@
-/*
- * Copyright (c) 2010, 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_ortho_projector/laser_ortho_projector_nodelet.h"
-
-typedef scan_tools::LaserOrthoProjectorNodelet LaserOrthoProjectorNodelet;
-
-PLUGINLIB_EXPORT_CLASS(LaserOrthoProjectorNodelet, nodelet::Nodelet)
-
-void LaserOrthoProjectorNodelet::onInit ()
-{
- NODELET_INFO("Initializing LaserOrthoProjector Nodelet");
-
- // TODO: Do we want the single threaded or multithreaded NH?
- ros::NodeHandle nh = getMTNodeHandle();
- ros::NodeHandle nh_private = getMTPrivateNodeHandle();
-
- laser_ortho_projector_ = new scan_tools::LaserOrthoProjector(nh, nh_private);
-}
diff --git a/laser_scan_matcher/CMakeLists.txt b/laser_scan_matcher/CMakeLists.txt
index ce20592..36b64b0 100644
--- a/laser_scan_matcher/CMakeLists.txt
+++ b/laser_scan_matcher/CMakeLists.txt
@@ -1,72 +1,59 @@
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 3.5)
project(laser_scan_matcher)
-# List C++ dependencies on ros packages
-set( ROS_CXX_DEPENDENCIES
- roscpp
- nodelet
- sensor_msgs
- tf
- pcl_ros
- pcl_conversions
- geometry_msgs
- nav_msgs)
-
-# Find catkin and all required ROS components
-find_package(catkin REQUIRED COMPONENTS ${ROS_CXX_DEPENDENCIES} rostest)
-find_package(PCL REQUIRED QUIET)
+find_package(ament_cmake REQUIRED)
+find_package(Eigen3 REQUIRED)
+find_package(geometry_msgs REQUIRED)
+find_package(nav_msgs REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(sensor_msgs REQUIRED)
+find_package(tf2 REQUIRED)
+find_package(tf2_geometry_msgs REQUIRED)
+find_package(tf2_ros REQUIRED)
+find_package(tf2_sensor_msgs REQUIRED)
# Find csm project
find_package(PkgConfig)
pkg_check_modules(csm REQUIRED csm)
-
-# Set include directories
-include_directories(include ${catkin_INCLUDE_DIRS} ${csm_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
link_directories(${csm_LIBRARY_DIRS})
-# Declare info that other packages need to import library generated here
-catkin_package(
- INCLUDE_DIRS include
- LIBRARIES laser_scan_matcher
- CATKIN_DEPENDS ${ROS_CXX_DEPENDENCIES}
-)
+include_directories(
+ include
+ ${csm_INCLUDE_DIRS}
+ ${EIGEN3_INCLUDE_DIRS}
+ )
#Create library
-add_library(laser_scan_matcher src/laser_scan_matcher.cpp)
-
-#Note we don't link against pcl as we're using header-only parts of the library
-target_link_libraries( laser_scan_matcher ${catkin_LIBRARIES} ${csm_LIBRARIES})
-add_dependencies(laser_scan_matcher ${csm_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
-
-#Create nodelet
-add_library(laser_scan_matcher_nodelet src/laser_scan_matcher_nodelet.cpp)
-target_link_libraries(laser_scan_matcher_nodelet laser_scan_matcher)
+add_library(${PROJECT_NAME}
+ src/laser_scan_matcher.cpp
+ src/param_handler.cpp)
+target_link_libraries(${PROJECT_NAME} ${csm_LIBRARIES})
#Create node
-add_executable(laser_scan_matcher_node src/laser_scan_matcher_node.cpp)
-target_link_libraries( laser_scan_matcher_node laser_scan_matcher )
+add_executable(laser_scan_matcher_node src/laser_scan_matcher_node.cpp)
+target_link_libraries(laser_scan_matcher_node ${PROJECT_NAME})
-#Install library
-install(TARGETS laser_scan_matcher laser_scan_matcher_nodelet
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
-
-#Install library includes
-install(DIRECTORY include/laser_scan_matcher/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} )
-
-#Install node
-install(TARGETS laser_scan_matcher_node
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} )
+ament_target_dependencies(${PROJECT_NAME}
+ csm
+ Eigen3
+ geometry_msgs
+ nav_msgs
+ rclcpp
+ sensor_msgs
+ tf2
+ tf2_geometry_msgs
+ tf2_ros
+ tf2_sensor_msgs
+)
-#Install nodelet description
-install(FILES laser_scan_matcher_nodelet.xml
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
+install(
+ TARGETS
+ ${PROJECT_NAME}
+ laser_scan_matcher_node
+ DESTINATION lib/${PROJECT_NAME})
-#Install demo files
-install(DIRECTORY demo
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
+install(DIRECTORY include/
+ DESTINATION include/
+)
-add_rostest(test/run.test)
-add_rostest(test/covariance.test)
+ament_package()
diff --git a/laser_scan_matcher/README.md b/laser_scan_matcher/README.md
new file mode 100644
index 0000000..47eb8d8
--- /dev/null
+++ b/laser_scan_matcher/README.md
@@ -0,0 +1,84 @@
+# laser_scan_matcher
+
+An incremental laser scan matcher, using Andrea Censi's Canonical Scan Matcher [1] implementation.
+
+- https://github.com/AndreaCensi/csm
+- https://censi.science/software/csm/
+
+ [1] A. Censi, "An ICP variant using a point-to-line metric" Proceedings of the
+IEEE International Conference on Robotics and Automation (ICRA), 2008
+
+
+# Subscribed topics
+
+| Topic | Type | Description |
+|-----|----|----|
+| **scan** | `sensor_msgs/LaserScan` | The input scan |
+| **imu/data (optional)** |`sensor_msgs/Imu` | Used to predict sensor yaw |
+| **odom (optional)** | `nav_msgs/Odometry` | Used to predict sensor pose |
+| **vel (optional)** | `geometry_msgs/Twist` or `geometry_msgs/TwistStamped` | Used to predict sensor pose |
+| **tf** | | A valid transform from the configured `odom_frame` to `base_frame` is required for an initial guess for the scan matcher |
+
+# Published topics
+
+| Topic | Type | Description |
+|-----|----|----|
+| **pose** | `geometry_msgs/PoseWithCovarianceStamped` | Pose message containing estimated pose of the `base frame` in the `odom frame` from the scan match |
+| **tf (optional)** | | Transform of from the `odom_frame` to `base_frame` based on scan match result |
+
+# General Parameters
+
+| Name | Type | Description | Default | Min | Max | Reconfigurable |
+|----|----|----|----|----|----|----|
+| **base_frame** | `string` | Which frame to use for the robot base | "base_link" | | |✗|
+| **heading_cov_scale** | `double` | Scaling to apply to ICP derived heading covariance | `1.0` | `0.0` | `1e8` |✓|
+| **heading_cov_offset** | `double` | Offset to apply to ICP derived heading covariance | `0.0` | `0.0` | `10.0` |✓|
+| **min_travel_distance** | `double` | Distance in meters to trigger a new keyframe | `0.5` | `0.0` | `10.0` |✓|
+| **min_travel_heading** | `double` | Angle in degrees to trigger a new keyframe. | `30.0` | `0.0` | `180.0` |✓|
+| **odom_frame** | `string` | Which frame to track odometry in | "odom" | | |✗|
+| **publish_tf** | `bool` | Whether to publish tf transform from `odom_frame` to `base_frame` | `true` | | |✗|
+| **tf_timeout** | `double` | TF timeout in seconds | `0.1` | `0.0` | `10.0` |✓|
+| **stamped_vel** |`bool` | Whether to subscribe to stamped twist messages | `false` | | |✗|
+| **use_imu** |`bool` | Whether to use imu messages for predicting the sensor yaw | `true` | | |✗|
+| **use_odom** |`bool` | Whether to use odom messages for predicting the sensor pose | `true` | | |✗|
+| **use_tf** |`bool` | Whether to use tf for predicting the sensor pose | `false` | | |✗|
+| **use_vel** |`bool` | Whether to use twist messages for predicting the sensor pose | `false` | | |✗|
+| **xy_cov_scale** | `double` | Scaling to apply to ICP derived xy position covariance | `1.0` | `0.0` | `1e8` |✓|
+| **xy_cov_offset** | `double` | Offset to apply to ICP derived xy position covariance | `0.0` | `0.0` | `10.0` |✓|
+
+# CSM Parameters
+
+| Name | Type | Description | Default | Min | Max | Reconfigurable |
+|----|----|----|----|----|----|----|
+| **alpha_test_threshold** | `double` | Threshold angle to discard correspondences, in degrees | `20.0` | `0.0` | `90.0` |✓|
+| **clustering_threshold** | `double` | Max distance, in meters, for staying in the same clustering | `0.25` | `0.0` | `1.0` |✓|
+| **debug_verify_tricks** | `bool` | Checks that find_correspondences_tricks gives the right answer | `false` | | |✓|
+| **do_alpha_test** | `bool` | Discard correspondences based on the angles | `false` | | |✓|
+| **do_compute_covariance** | `bool` | Compute the covariance of the ICP | `true` | | |✓|
+| **do_visibility_test** | `bool` | Use visibility test trick for matching | `false` | | |✓|
+| **epsilon_theta** | `double` | A threshold for stopping, in radians | `1e-6` | `1e-10` | `1e-1` |✓|
+| **epsilon_xy** | `double` | A threshold for stopping, in meters | `1e-6` | `1e-10` | `1e-1` |✓|
+| **max_angular_correction_deg** | `double` | Max distance, in meters, for a correspondence to be valid | `0.3` | `0.0` | `10.0` |✓|
+| **max_correspondence_dist** | `double` | Max angular displacement, in degrees, between scans | `45` | `0.0` | `90.0` |✓|
+| **max_iterations** | `int` | Max ICP cycle iterations | `10` | `1` | `100` |✓|
+| **max_linear_correction** | `double` | Max translation, in meters, between scans | `0.5` | `0.0` | `10.0` |✓|
+| **orientation_neighbourhood** | `int` | Number of neighbour rays used to estimate the orientation | `20` | `0` | `100` |✓|
+| **outliers_adaptive_mult** | `double` | Threshold multiplier for error at chosen percentile | `2.0` | `0.0` | `10.0` |✓|
+| **outliers_adaptive_order** | `double` | Percentile `[0, 1]` to use for adaptive outlier detection | `0.7` | `0.0` | `1.0` |✓|
+| **outliers_max_perc** | `double` | Percentage `[0, 1]` of correspondences to consider with lowest error | `0.9` | `0.0` | `1.0` |✓|
+| **outliers_remove_doubles** | `bool` | Do not allow two different correspondences to share a point | `true` | | |✓|
+| **restart** | `bool` | Restart if error is over threshold | `false` | | |✓|
+| **restart_dt** | `double` | Displacement, in meters, for restarting | `1.0` | `0.0` | `10.0` |✓|
+| **restart_dtheta** | `double` | Displacement, in radians, for restarting | `0.1` | `0.0` | `1.57` |✓|
+| **restart_threshold_mean_error** | `double` | Threshold, in meters, for restarting | `0.01` | `0.0` | `1.0` |✓|
+| **sigma** | `double` | Noise in the scan, in meters | `0.01` | `0.0` | `1.0` |✓|
+| **use_corr_tricks** | `bool` | Use smart tricks for finding correspondences | `true` | | |✓|
+| **use_ml_weights** | `bool` | Use the 'true_alpha' or 'alpha' field to weight the impact of each correspondence | `false` | | |✓|
+| **use_point_to_line_distance** | `bool` | Use point-to-line ICP. If false, it's vanilla ICP | `true` | | |✓|
+| **use_sigma_weights** | `bool` | Use the 'readings_sigma' field of the second scan to weight the correspondence | `false` | | |✓|
+
+# License
+
+Note: This package is licensed with [BSD-3-Clause](https://opensource.org/licenses/BSD-3-Clause), but links to the version
+ of [CSM](https://github.com/AndreaCensi/csm) which uses [eigen](https://eigen.tuxfamily.org/). CSM itself
+ is [LGPL-3.0](https://opensource.org/licenses/LGPL-3.0), while eigen is [MPL-2.0](https://opensource.org/licenses/MPL-2.0)
\ No newline at end of file
diff --git a/laser_scan_matcher/demo/demo.bag b/laser_scan_matcher/demo/demo.bag
deleted file mode 100644
index 4e289b7..0000000
Binary files a/laser_scan_matcher/demo/demo.bag and /dev/null differ
diff --git a/laser_scan_matcher/demo/demo.launch b/laser_scan_matcher/demo/demo.launch
deleted file mode 100644
index 8e85de8..0000000
--- a/laser_scan_matcher/demo/demo.launch
+++ /dev/null
@@ -1,40 +0,0 @@
-
-
-
-
-
-
- #### set up data playback from bag #############################
-
-
-
-
-
-
-
-
-
-
- #### publish an example base_link -> laser transform ###########
-
-
-
- #### start the laser scan_matcher ##############################
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/laser_scan_matcher/demo/demo.rviz b/laser_scan_matcher/demo/demo.rviz
deleted file mode 100644
index 754e9ce..0000000
--- a/laser_scan_matcher/demo/demo.rviz
+++ /dev/null
@@ -1,162 +0,0 @@
-Panels:
- - Class: rviz/Displays
- Help Height: 78
- Name: Displays
- Property Tree Widget:
- Expanded:
- - /Global Options1
- - /Status1
- - /Grid1
- - /LaserScan1
- - /TF1
- - /TF1/Frames1
- Splitter Ratio: 0.5
- Tree Height: 434
- - Class: rviz/Selection
- Name: Selection
- - Class: rviz/Tool Properties
- Expanded:
- - /2D Pose Estimate1
- - /2D Nav Goal1
- - /Publish Point1
- Name: Tool Properties
- Splitter Ratio: 0.588679
- - Class: rviz/Views
- Expanded:
- - /Current View1
- Name: Views
- Splitter Ratio: 0.5
- - Class: rviz/Time
- Experimental: false
- Name: Time
- SyncMode: 0
- SyncSource: LaserScan
-Visualization Manager:
- Class: ""
- Displays:
- - Alpha: 0.5
- Cell Size: 1
- Class: rviz/Grid
- Color: 160; 160; 164
- Enabled: true
- Line Style:
- Line Width: 0.03
- Value: Lines
- Name: Grid
- Normal Cell Count: 0
- Offset:
- X: 0
- Y: 0
- Z: 0
- Plane: XY
- Plane Cell Count: 10
- Reference Frame:
- Value: true
- - Alpha: 0.2
- Autocompute Intensity Bounds: true
- Autocompute Value Bounds:
- Max Value: 10
- Min Value: -10
- Value: true
- Axis: Z
- Channel Name: intensity
- Class: rviz/LaserScan
- Color: 255; 0; 0
- Color Transformer: FlatColor
- Decay Time: 0
- Enabled: true
- Invert Rainbow: false
- Max Color: 255; 0; 0
- Max Intensity: 4096
- Min Color: 0; 0; 0
- Min Intensity: 0
- Name: LaserScan
- Position Transformer: XYZ
- Queue Size: 10
- Selectable: true
- Size (Pixels): 3
- Size (m): 0.01
- Style: Flat Squares
- Topic: /scan
- Use Fixed Frame: true
- Use rainbow: true
- Value: true
- - Class: rviz/TF
- Enabled: true
- Frame Timeout: 15
- Frames:
- All Enabled: true
- base_link:
- Value: true
- laser:
- Value: true
- world:
- Value: true
- Marker Scale: 1
- Name: TF
- Show Arrows: true
- Show Axes: true
- Show Names: true
- Tree:
- world:
- base_link:
- laser:
- {}
- Update Interval: 0
- Value: true
- Enabled: true
- Global Options:
- Background Color: 0; 0; 0
- Fixed Frame: world
- Frame Rate: 30
- Name: root
- Tools:
- - Class: rviz/Interact
- Hide Inactive Objects: true
- - Class: rviz/MoveCamera
- - Class: rviz/Select
- - Class: rviz/FocusCamera
- - Class: rviz/Measure
- - Class: rviz/SetInitialPose
- Topic: /initialpose
- - Class: rviz/SetGoal
- Topic: /move_base_simple/goal
- - Class: rviz/PublishPoint
- Single click: true
- Topic: /clicked_point
- Value: true
- Views:
- Current:
- Angle: 0
- Class: rviz/TopDownOrtho
- Enable Stereo Rendering:
- Stereo Eye Separation: 0.06
- Stereo Focal Distance: 1
- Swap Stereo Eyes: false
- Value: false
- Name: Current View
- Near Clip Distance: 0.01
- Scale: 150
- Target Frame:
- Value: TopDownOrtho (rviz)
- X: 0
- Y: 0
- Saved: ~
-Window Geometry:
- Displays:
- collapsed: false
- Height: 721
- Hide Left Dock: false
- Hide Right Dock: false
- QMainWindow State: 000000ff00000000fd00000004000000000000013c0000023dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000360000023d000000b700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000023dfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000360000023d0000009b00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004000000003efc0100000002fb0000000800540069006d00650100000000000004000000024500fffffffb0000000800540069006d00650100000000000004500000000000000000000001a90000023d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
- Selection:
- collapsed: false
- Time:
- collapsed: false
- Tool Properties:
- collapsed: false
- Views:
- collapsed: false
- Width: 1024
- X: -2
- Y: -2
diff --git a/laser_scan_matcher/demo/demo_gmapping.launch b/laser_scan_matcher/demo/demo_gmapping.launch
deleted file mode 100644
index 58b6567..0000000
--- a/laser_scan_matcher/demo/demo_gmapping.launch
+++ /dev/null
@@ -1,68 +0,0 @@
-
-
-
-
- #### set up data playback from bag #############################
-
-
-
-
-
- #### publish an example base_link -> laser transform ###########
-
-
-
- #### start rviz ################################################
-
-
-
- #### start the laser scan_matcher ##############################
-
-
-
-
-
-
-
-
- #### start gmapping ############################################
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/laser_scan_matcher/demo/demo_gmapping.rviz b/laser_scan_matcher/demo/demo_gmapping.rviz
deleted file mode 100644
index 6706528..0000000
--- a/laser_scan_matcher/demo/demo_gmapping.rviz
+++ /dev/null
@@ -1,175 +0,0 @@
-Panels:
- - Class: rviz/Displays
- Help Height: 78
- Name: Displays
- Property Tree Widget:
- Expanded:
- - /Global Options1
- - /Status1
- - /Grid1
- - /LaserScan1
- - /TF1
- - /TF1/Frames1
- - /TF1/Frames1/odom1
- - /Map1
- Splitter Ratio: 0.5
- Tree Height: 434
- - Class: rviz/Selection
- Name: Selection
- - Class: rviz/Tool Properties
- Expanded:
- - /2D Pose Estimate1
- - /2D Nav Goal1
- - /Publish Point1
- Name: Tool Properties
- Splitter Ratio: 0.588679
- - Class: rviz/Views
- Expanded:
- - /Current View1
- Name: Views
- Splitter Ratio: 0.5
- - Class: rviz/Time
- Experimental: false
- Name: Time
- SyncMode: 0
- SyncSource: LaserScan
-Visualization Manager:
- Class: ""
- Displays:
- - Alpha: 0.5
- Cell Size: 1
- Class: rviz/Grid
- Color: 160; 160; 164
- Enabled: true
- Line Style:
- Line Width: 0.03
- Value: Lines
- Name: Grid
- Normal Cell Count: 0
- Offset:
- X: 0
- Y: 0
- Z: 0
- Plane: XY
- Plane Cell Count: 10
- Reference Frame:
- Value: true
- - Alpha: 1
- Autocompute Intensity Bounds: true
- Autocompute Value Bounds:
- Max Value: 10
- Min Value: -10
- Value: true
- Axis: Z
- Channel Name: intensity
- Class: rviz/LaserScan
- Color: 255; 0; 0
- Color Transformer: FlatColor
- Decay Time: 0
- Enabled: true
- Invert Rainbow: false
- Max Color: 255; 0; 0
- Max Intensity: 4096
- Min Color: 0; 0; 0
- Min Intensity: 0
- Name: LaserScan
- Position Transformer: XYZ
- Queue Size: 10
- Selectable: true
- Size (Pixels): 3
- Size (m): 0.01
- Style: Flat Squares
- Topic: /scan
- Use Fixed Frame: true
- Use rainbow: true
- Value: true
- - Class: rviz/TF
- Enabled: true
- Frame Timeout: 15
- Frames:
- All Enabled: true
- base_link:
- Value: true
- laser:
- Value: true
- map:
- Value: true
- odom:
- Value: true
- Marker Scale: 1
- Name: TF
- Show Arrows: true
- Show Axes: true
- Show Names: true
- Tree:
- map:
- odom:
- base_link:
- laser:
- {}
- Update Interval: 0
- Value: true
- - Alpha: 0.7
- Class: rviz/Map
- Color Scheme: map
- Draw Behind: false
- Enabled: true
- Name: Map
- Topic: /map
- Value: true
- Enabled: true
- Global Options:
- Background Color: 0; 0; 0
- Fixed Frame: map
- Frame Rate: 30
- Name: root
- Tools:
- - Class: rviz/Interact
- Hide Inactive Objects: true
- - Class: rviz/MoveCamera
- - Class: rviz/Select
- - Class: rviz/FocusCamera
- - Class: rviz/Measure
- - Class: rviz/SetInitialPose
- Topic: /initialpose
- - Class: rviz/SetGoal
- Topic: /move_base_simple/goal
- - Class: rviz/PublishPoint
- Single click: true
- Topic: /clicked_point
- Value: true
- Views:
- Current:
- Angle: 0
- Class: rviz/TopDownOrtho
- Enable Stereo Rendering:
- Stereo Eye Separation: 0.06
- Stereo Focal Distance: 1
- Swap Stereo Eyes: false
- Value: false
- Name: Current View
- Near Clip Distance: 0.01
- Scale: 150
- Target Frame:
- Value: TopDownOrtho (rviz)
- X: 0
- Y: 0
- Saved: ~
-Window Geometry:
- Displays:
- collapsed: false
- Height: 721
- Hide Left Dock: false
- Hide Right Dock: false
- QMainWindow State: 000000ff00000000fd00000004000000000000013c0000023dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000360000023d000000b700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000023dfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000360000023d0000009b00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004000000003efc0100000002fb0000000800540069006d00650100000000000004000000024500fffffffb0000000800540069006d00650100000000000004500000000000000000000001a90000023d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
- Selection:
- collapsed: false
- Time:
- collapsed: false
- Tool Properties:
- collapsed: false
- Views:
- collapsed: false
- Width: 1024
- X: -2
- Y: -2
diff --git a/laser_scan_matcher/demo/demo_vel.launch b/laser_scan_matcher/demo/demo_vel.launch
deleted file mode 100644
index d7133df..0000000
--- a/laser_scan_matcher/demo/demo_vel.launch
+++ /dev/null
@@ -1,48 +0,0 @@
-
-
-
-
- #### set up data playback from bag #############################
-
-
-
-
-
-
-
- #### publish an example base_link -> laser transform ###########
-
-
-
- #### start the laser scan_matcher ##############################
-
-
-
-
-
-
-
-
- #### start the alpha-beta filter ###############################
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/laser_scan_matcher/include/laser_scan_matcher/laser_scan_matcher.h b/laser_scan_matcher/include/laser_scan_matcher/laser_scan_matcher.h
index 6b11aad..6accd93 100644
--- a/laser_scan_matcher/include/laser_scan_matcher/laser_scan_matcher.h
+++ b/laser_scan_matcher/include/laser_scan_matcher/laser_scan_matcher.h
@@ -35,87 +35,71 @@
* on Robotics and Automation (ICRA), 2008
*/
-#ifndef LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
-#define LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include // csm defines min and max, but Eigen complains
+#pragma once
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include
#undef min
#undef max
-namespace scan_tools
-{
+namespace scan_tools {
-class LaserScanMatcher
+class LaserScanMatcher: public rclcpp::Node
{
public:
-
- LaserScanMatcher(ros::NodeHandle nh, ros::NodeHandle nh_private);
- ~LaserScanMatcher();
+ LaserScanMatcher();
+ ~LaserScanMatcher() = default;
private:
-
- typedef pcl::PointXYZ PointT;
- typedef pcl::PointCloud PointCloudT;
-
// **** ros
- ros::NodeHandle nh_;
- ros::NodeHandle nh_private_;
-
- ros::Subscriber scan_subscriber_;
- ros::Subscriber cloud_subscriber_;
- ros::Subscriber odom_subscriber_;
- ros::Subscriber imu_subscriber_;
- ros::Subscriber vel_subscriber_;
+ rclcpp::TimerBase::SharedPtr init_timer_;
- tf::TransformListener tf_listener_;
- tf::TransformBroadcaster tf_broadcaster_;
+ rclcpp::Subscription::SharedPtr scan_subscriber_;
+ rclcpp::Subscription::SharedPtr odom_subscriber_;
+ rclcpp::Subscription::SharedPtr imu_subscriber_;
+ rclcpp::Subscription::SharedPtr vel_subscriber_;
+ rclcpp::Subscription::SharedPtr vel_stamped_subscriber_;
- tf::Transform base_from_laser_; // static, cached
- tf::Transform laser_from_base_; // static, cached
+ std::shared_ptr tf_;
+ std::shared_ptr tf_broadcaster_;
+ std::shared_ptr tf_buffer_;
- ros::Publisher pose_publisher_;
- ros::Publisher pose_stamped_publisher_;
- ros::Publisher pose_with_covariance_publisher_;
- ros::Publisher pose_with_covariance_stamped_publisher_;
+ tf2::Transform base_from_laser_; // static, cached
+ tf2::Transform laser_from_base_; // static, cached
- // **** parameters
+ rclcpp::Publisher::SharedPtr pose_publisher_;
- std::string base_frame_;
- std::string fixed_frame_;
- double cloud_range_min_;
- double cloud_range_max_;
- double cloud_res_;
- bool publish_tf_;
- bool publish_pose_;
- bool publish_pose_with_covariance_;
- bool publish_pose_stamped_;
- bool publish_pose_with_covariance_stamped_;
- std::vector position_covariance_;
- std::vector orientation_covariance_;
+ // **** coordinate parameters
+ std::string base_frame_ = "base_link";
+ std::string odom_frame_ = "odom";
+ bool publish_tf_ = false;
+ double tf_timeout_ = 0.1;
- bool use_cloud_input_;
+ // **** keyframe parameters
+ double min_travel_distance_ = 0.5;
+ double min_travel_heading_ = 30.0;
- double kf_dist_linear_;
- double kf_dist_linear_sq_;
- double kf_dist_angular_;
+ // **** covariance parameters
+ double xy_cov_scale_ = 1.0;
+ double xy_cov_offset_ = 0.0;
+ double heading_cov_scale_ = 1.0;
+ double heading_cov_offset_ = 0.0;
// **** What predictions are available to speed up the ICP?
// 1) imu - [theta] from imu yaw angle - /imu topic
@@ -123,61 +107,50 @@ class LaserScanMatcher
// 3) tf - [x, y, theta] from /tf topic
// 3) velocity [vx, vy, vtheta], usually from ab-filter - /vel.
// If more than one is enabled, priority is tf > imu > odom > velocity
-
- bool use_imu_;
- bool use_odom_;
- bool use_tf_;
- double tf_timeout_;
- bool use_vel_;
- bool stamped_vel_;
+ bool use_imu_ = true;
+ bool use_odom_ = true;
+ bool use_tf_ = false;
+ bool use_vel_ = false;
+ bool stamped_vel_ = false;
// **** state variables
+ bool initialized_ = false;
+ ParamHandler params_;
- boost::mutex mutex_;
-
- bool initialized_;
- bool received_imu_;
- bool received_odom_;
- bool received_vel_;
-
- tf::Transform last_base_in_fixed_; // pose of the base of the last scan in fixed frame
- tf::Transform keyframe_base_in_fixed_; // pose of the base of last keyframe scan in fixed frame
+ tf2::Transform last_base_in_fixed_; // pose of the base of the last scan in fixed frame
+ tf2::Transform keyframe_base_in_fixed_; // pose of the base of last keyframe scan in fixed frame
- ros::Time last_icp_time_;
+ rclcpp::Time last_icp_time_;
- sensor_msgs::Imu latest_imu_msg_;
- tf::Quaternion last_used_imu_orientation_;
- nav_msgs::Odometry latest_odom_msg_;
- tf::Transform last_used_odom_pose_;
+ sensor_msgs::msg::Imu::SharedPtr latest_imu_msg_;
+ nav_msgs::msg::Odometry::SharedPtr latest_odom_msg_;
+ geometry_msgs::msg::Twist::SharedPtr latest_vel_msg_;
- geometry_msgs::Twist latest_vel_msg_;
+ tf2::Quaternion last_used_imu_orientation_;
+ tf2::Transform last_used_odom_pose_;
std::vector a_cos_;
std::vector a_sin_;
sm_params input_;
sm_result output_;
- LDP prev_ldp_scan_;
+ LDP keyframe_laser_data_;
- // **** methods
+ // **** methods
void initParams();
- void processScan(LDP& curr_ldp_scan, const ros::Time& time);
+ void processScan(const sensor_msgs::msg::LaserScan::SharedPtr scan_msg);
- void laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& scan_msg,
- LDP& ldp);
- void PointCloudToLDP(const PointCloudT::ConstPtr& cloud,
- LDP& ldp);
+ void laserScanToLDP(const sensor_msgs::msg::LaserScan::SharedPtr& scan, LDP& ldp);
- void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
- void cloudCallback (const PointCloudT::ConstPtr& cloud);
+ void scanCallback(const sensor_msgs::msg::LaserScan::SharedPtr scan_msg);
- void odomCallback(const nav_msgs::Odometry::ConstPtr& odom_msg);
- void imuCallback (const sensor_msgs::Imu::ConstPtr& imu_msg);
- void velCallback (const geometry_msgs::Twist::ConstPtr& twist_msg);
- void velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr& twist_msg);
+ void odomCallback(const nav_msgs::msg::Odometry::SharedPtr odom_msg);
+ void imuCallback(const sensor_msgs::msg::Imu::SharedPtr imu_msg);
+ void velCallback(const geometry_msgs::msg::Twist::SharedPtr twist_msg);
+ void velStmpCallback(const geometry_msgs::msg::TwistStamped::SharedPtr twist_msg);
- void createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
+ void createCache(const sensor_msgs::msg::LaserScan::SharedPtr& scan_msg);
/**
* Cache the static transform between the base and laser.
@@ -186,17 +159,21 @@ class LaserScanMatcher
*
* @returns True if the transform was found, false otherwise.
*/
- bool getBaseLaserTransform(const std::string& frame_id);
+ bool getBaseToLaserTf (const std::string& frame_id);
- bool newKeyframeNeeded(const tf::Transform& d);
+ bool getTfOffset(
+ const std::string& frame_id,
+ const rclcpp::Time& target_stamp,
+ const rclcpp::Time& source_stamp,
+ tf2::Transform& transform);
- tf::Transform getPrediction(const ros::Time& stamp);
+ bool newKeyframeNeeded(const tf2::Transform& d);
- void createTfFromXYTheta(double x, double y, double theta, tf::Transform& t);
+ tf2::Transform getPrediction(const rclcpp::Time& stamp);
- Eigen::Matrix2f getLaserRotation(const tf::Transform& odom_pose) const;
-};
+ void createTfFromXYTheta(double x, double y, double theta, tf2::Transform& t);
-} // namespace scan_tools
+ Eigen::Matrix2f getLaserRotation(const tf2::Transform& odom_pose);
+};
-#endif // LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
+} // namespace scan_tools
diff --git a/laser_scan_matcher/include/laser_scan_matcher/laser_scan_matcher_nodelet.h b/laser_scan_matcher/include/laser_scan_matcher/laser_scan_matcher_nodelet.h
deleted file mode 100644
index 24efdae..0000000
--- a/laser_scan_matcher/include/laser_scan_matcher/laser_scan_matcher_nodelet.h
+++ /dev/null
@@ -1,59 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-/* This package uses Canonical Scan Matcher [1], written by
- * Andrea Censi
- *
- * [1] A. Censi, "An ICP variant using a point-to-line metric"
- * Proceedings of the IEEE International Conference
- * on Robotics and Automation (ICRA), 2008
- */
-
-#ifndef LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_NODELET_H
-#define LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_NODELET_H
-
-#include
-#include
-
-#include
-
-namespace scan_tools {
-
-class LaserScanMatcherNodelet : public nodelet::Nodelet
-{
- public:
- virtual void onInit ();
-
- private:
- boost::shared_ptr scan_matcher_;
-};
-
-} // namespace scan_tools
-
-#endif // LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_NODELET_H
diff --git a/laser_scan_matcher/include/laser_scan_matcher/param_handler.h b/laser_scan_matcher/include/laser_scan_matcher/param_handler.h
new file mode 100644
index 0000000..1280d23
--- /dev/null
+++ b/laser_scan_matcher/include/laser_scan_matcher/param_handler.h
@@ -0,0 +1,114 @@
+#pragma once
+
+#include
+
+namespace scan_tools {
+
+class ParamHandler {
+public:
+ ParamHandler() = default;
+ ~ParamHandler() = default;
+
+ void initialize(rclcpp::Node::SharedPtr node);
+
+ void registerCallback();
+
+ /**
+ * Register a non-dynamic parameter and return it's value.
+ *
+ * @param[in] name Parameter name
+ * @param[in] default_val Default parameter value
+ * @param[in] description Parameter description
+ *
+ * @returns the value of the parameter.
+ */
+ template
+ T param(const std::string& name, const T& default_val, const std::string& description) {
+ auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
+ descriptor.description = description;
+ descriptor.read_only = true;
+ node_->declare_parameter(name, rclcpp::ParameterValue(default_val), descriptor);
+ return node_->get_parameter(name).get_value();
+ }
+
+ /**
+ * Register a dynamic parameter without any range constraint and populate
+ * the parameter variable with the current value.
+ *
+ * @param[out] param Reference to parameter variable
+ * @param[in] name Parameter name
+ * @param[in] default_val Default parameter value
+ * @param[in] description Parameter description
+ */
+ template
+ void register_param(T* param, const std::string& name, const T& default_val, const std::string& description) {
+ auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
+ descriptor.description = description;
+ descriptor.read_only = false;
+ node_->declare_parameter(name, rclcpp::ParameterValue(default_val), descriptor);
+ auto p = node_->get_parameter(name);
+ *param = p.get_value();
+
+ if (p.get_type() == rclcpp::ParameterType::PARAMETER_BOOL) {
+ bool_params_[name] = static_cast(static_cast(param));
+ }
+ else if (p.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE) {
+ double_params_[name] = static_cast(static_cast(param));
+ }
+ else if (p.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER) {
+ int_params_[name] = static_cast(static_cast(param));
+ }
+ else {
+ RCLCPP_ERROR(node_->get_logger(), "Unsupported dynamic parameter type: %s for parameter: %s", p.get_type_name().c_str(), name.c_str());
+ }
+ }
+
+ /**
+ * Register a dynamic bool parameter stored in an integer variable and
+ * populate the parameter variable with the current value.
+ *
+ * @param[out] param Reference to parameter variable
+ * @param[in] name Parameter name
+ * @param[in] default_val Default parameter value
+ * @param[in] description Parameter description
+ */
+ void register_param(int* param, const std::string& name, bool default_val, const std::string& description);
+
+ /**
+ * Register a dynamic integer parameter with a range constraint and populate
+ * the parameter variable with the current value.
+ *
+ * @param[out] param Reference to parameter variable
+ * @param[in] name Parameter name
+ * @param[in] default_val Default parameter value
+ * @param[in] description Parameter description
+ * @param[in] min Min value
+ * @param[in] max Max value
+ */
+ void register_param(int* param, const std::string& name, int default_val, const std::string& description, int min, int max);
+
+ /**
+ * Register a dynamic double parameter with a range constraint and populate
+ * the parameter variable with the current value.
+ *
+ * @param[out] param Reference to parameter variable
+ * @param[in] name Parameter name
+ * @param[in] default_val Default parameter value
+ * @param[in] description Parameter description
+ * @param[in] min Min value
+ * @param[in] max Max value
+ */
+ void register_param(double* param, const std::string& name, double default_val, const std::string& description, double min, double max);
+
+private:
+ rclcpp::Node::SharedPtr node_;
+ rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr params_callback_handle_;
+ std::unordered_map bool_params_;
+ std::unordered_map double_params_;
+ std::unordered_map int_params_;
+ std::unordered_map string_params_;
+
+ rcl_interfaces::msg::SetParametersResult parametersCallback(const std::vector ¶meters);
+};
+
+} // scan_tools
diff --git a/laser_scan_matcher/laser_scan_matcher_nodelet.xml b/laser_scan_matcher/laser_scan_matcher_nodelet.xml
deleted file mode 100644
index 3fbb74f..0000000
--- a/laser_scan_matcher/laser_scan_matcher_nodelet.xml
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
-
- Laser Scan Matcher nodelet publisher.
-
-
-
diff --git a/laser_scan_matcher/package.xml b/laser_scan_matcher/package.xml
index 9fb5978..934d620 100644
--- a/laser_scan_matcher/package.xml
+++ b/laser_scan_matcher/package.xml
@@ -1,4 +1,6 @@
-
+
+
+laser_scan_matcher0.3.3
@@ -17,32 +19,24 @@
BSDLGPLv3
- catkin
+ ament_cmake
+ pkg-config
- csm
- geometry_msgs
- libpcl-all-dev
- nav_msgs
- nodelet
- pcl_conversions
- pcl_ros
- roscpp
- sensor_msgs
- tf
+ csm
+ eigen
+ geometry_msgs
+ nav_msgs
+ rclcpp
+ sensor_msgs
+ tf2
+ tf2_geometry_msgs
+ tf2_ros
+ tf2_sensor_msgs
- csm
- geometry_msgs
- libpcl-all
- nav_msgs
- nodelet
- pcl_ros
- pcl_conversions
- roscpp
- sensor_msgs
- tf
+ ament_lint_auto
+ ament_lint_common
-
+ ament_cmake
-
diff --git a/laser_scan_matcher/src/laser_scan_matcher.cpp b/laser_scan_matcher/src/laser_scan_matcher.cpp
index 7498057..60b9417 100644
--- a/laser_scan_matcher/src/laser_scan_matcher.cpp
+++ b/laser_scan_matcher/src/laser_scan_matcher.cpp
@@ -27,8 +27,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*/
-/* This package uses Canonical Scan Matcher [1], written by
- * Andrea Censi
+/* This package uses Canonical Scan Matcher [1], written by Andrea Censi
*
* [1] A. Censi, "An ICP variant using a point-to-line metric"
* Proceedings of the IEEE International Conference
@@ -36,470 +35,258 @@
*/
#include
-#include
-#include
-#include
-namespace scan_tools
-{
-
-LaserScanMatcher::LaserScanMatcher(ros::NodeHandle nh, ros::NodeHandle nh_private):
- nh_(nh),
- nh_private_(nh_private),
- initialized_(false),
- received_imu_(false),
- received_odom_(false),
- received_vel_(false)
-{
- ROS_INFO("Starting LaserScanMatcher");
+#include
- // **** init parameters
+#include
+#include
+#include
- initParams();
+using namespace std::chrono_literals;
- // **** state variables
+namespace scan_tools {
- last_base_in_fixed_.setIdentity();
- keyframe_base_in_fixed_.setIdentity();
- last_used_odom_pose_.setIdentity();
- input_.laser[0] = 0.0;
- input_.laser[1] = 0.0;
- input_.laser[2] = 0.0;
-
- // Initialize output_ vectors as Null for error-checking
- output_.cov_x_m = 0;
- output_.dx_dy1_m = 0;
- output_.dx_dy2_m = 0;
-
- // **** publishers
+LaserScanMatcher::LaserScanMatcher() :
+ rclcpp::Node("laser_scan_matcher"),
+ tf_buffer_(std::make_shared(get_clock()))
+{
+ RCLCPP_INFO(get_logger(), "Starting LaserScanMatcher");
- if (publish_pose_)
+ init_timer_ = create_wall_timer(100ms, [&]()
{
- pose_publisher_ = nh_.advertise(
- "pose2D", 5);
- }
+ // **** init parameters
+ initParams();
- if (publish_pose_stamped_)
- {
- pose_stamped_publisher_ = nh_.advertise(
- "pose_stamped", 5);
- }
+ // **** state variables
+ last_base_in_fixed_.setIdentity();
+ keyframe_base_in_fixed_.setIdentity();
+ last_used_odom_pose_.setIdentity();
+ input_.laser[0] = 0.0;
+ input_.laser[1] = 0.0;
+ input_.laser[2] = 0.0;
- if (publish_pose_with_covariance_)
- {
- pose_with_covariance_publisher_ = nh_.advertise(
- "pose_with_covariance", 5);
- }
+ // Initialize output_ vectors as Null for error-checking
+ output_.cov_x_m = nullptr;
+ output_.dx_dy1_m = nullptr;
+ output_.dx_dy2_m = nullptr;
- if (publish_pose_with_covariance_stamped_)
- {
- pose_with_covariance_stamped_publisher_ = nh_.advertise(
- "pose_with_covariance_stamped", 5);
- }
+ // **** publishers
+ pose_publisher_ = create_publisher("laser_pose", rclcpp::SystemDefaultsQoS());
- // *** subscribers
+ if (publish_tf_) {
+ tf_broadcaster_ = std::make_shared(*this);
+ }
- if (use_cloud_input_)
- {
- cloud_subscriber_ = nh_.subscribe(
- "cloud", 1, &LaserScanMatcher::cloudCallback, this);
- }
- else
- {
- scan_subscriber_ = nh_.subscribe(
- "scan", 1, &LaserScanMatcher::scanCallback, this);
- }
+ // **** subscribers
+ scan_subscriber_ = create_subscription(
+ "scan", rclcpp::SensorDataQoS(), std::bind(&LaserScanMatcher::scanCallback, this, std::placeholders::_1));
+ tf_ = std::make_shared(*tf_buffer_);
- if (use_imu_)
- {
- imu_subscriber_ = nh_.subscribe(
- "imu/data", 1, &LaserScanMatcher::imuCallback, this);
- }
- if (use_odom_)
- {
- odom_subscriber_ = nh_.subscribe(
- "odom", 1, &LaserScanMatcher::odomCallback, this);
- }
- if (use_vel_)
- {
- if (stamped_vel_)
- vel_subscriber_ = nh_.subscribe(
- "vel", 1, &LaserScanMatcher::velStmpCallback, this);
- else
- vel_subscriber_ = nh_.subscribe(
- "vel", 1, &LaserScanMatcher::velCallback, this);
- }
-}
-
-LaserScanMatcher::~LaserScanMatcher()
-{
- ROS_INFO("Destroying LaserScanMatcher");
+ if (use_imu_)
+ {
+ imu_subscriber_ = create_subscription(
+ "imu/data", rclcpp::SensorDataQoS(), std::bind(&LaserScanMatcher::imuCallback, this, std::placeholders::_1));
+ }
+ if (use_odom_)
+ {
+ odom_subscriber_ = create_subscription(
+ "odom", 10, std::bind(&LaserScanMatcher::odomCallback, this, std::placeholders::_1));
+ }
+ if (use_vel_)
+ {
+ if (stamped_vel_)
+ {
+ vel_stamped_subscriber_ = create_subscription(
+ "vel", rclcpp::SensorDataQoS(), std::bind(&LaserScanMatcher::velStmpCallback, this, std::placeholders::_1));
+ }
+ else
+ {
+ vel_subscriber_ = create_subscription(
+ "vel", rclcpp::SensorDataQoS(), std::bind(&LaserScanMatcher::velCallback, this, std::placeholders::_1));
+ }
+ }
+ });
}
-void LaserScanMatcher::initParams()
-{
- if (!nh_private_.getParam ("base_frame", base_frame_))
- base_frame_ = "base_link";
- if (!nh_private_.getParam ("fixed_frame", fixed_frame_))
- fixed_frame_ = "world";
-
- // **** input type - laser scan, or point clouds?
- // if false, will subscribe to LaserScan msgs on /scan.
- // if true, will subscribe to PointCloud2 msgs on /cloud
-
- if (!nh_private_.getParam ("use_cloud_input", use_cloud_input_))
- use_cloud_input_= false;
-
- if (use_cloud_input_)
- {
- if (!nh_private_.getParam ("cloud_range_min", cloud_range_min_))
- cloud_range_min_ = 0.1;
- if (!nh_private_.getParam ("cloud_range_max", cloud_range_max_))
- cloud_range_max_ = 50.0;
- if (!nh_private_.getParam ("cloud_res", cloud_res_))
- cloud_res_ = 0.05;
-
- input_.min_reading = cloud_range_min_;
- input_.max_reading = cloud_range_max_;
- }
-
- // **** keyframe params: when to generate the keyframe scan
- // if either is set to 0, reduces to frame-to-frame matching
-
- if (!nh_private_.getParam ("kf_dist_linear", kf_dist_linear_))
- kf_dist_linear_ = 0.10;
- if (!nh_private_.getParam ("kf_dist_angular", kf_dist_angular_))
- kf_dist_angular_ = 10.0 * (M_PI / 180.0);
-
- kf_dist_linear_sq_ = kf_dist_linear_ * kf_dist_linear_;
-
- // **** What predictions are available to speed up the ICP?
- // 1) imu - [theta] from imu yaw angle - /imu topic
- // 2) odom - [x, y, theta] from wheel odometry - /odom topic
- // 3) vel - [x, y, theta] from velocity predictor - see alpha-beta predictors - /vel topic
- // If more than one is enabled, priority is imu > odom > vel
-
- if (!nh_private_.getParam ("use_imu", use_imu_))
- use_imu_ = true;
- if (!nh_private_.getParam ("use_odom", use_odom_))
- use_odom_ = true;
- if (!nh_private_.getParam ("use_tf", use_tf_))
- use_tf_ = true;
- if (!nh_private_.getParam ("tf_timeout", tf_timeout_))
- tf_timeout_ = 0.1;
- if (!nh_private_.getParam ("use_vel", use_vel_))
- use_vel_ = false;
-
- // **** Are velocity input messages stamped?
- // if false, will subscribe to Twist msgs on /vel
- // if true, will subscribe to TwistStamped msgs on /vel
- if (!nh_private_.getParam ("stamped_vel", stamped_vel_))
- stamped_vel_ = false;
-
- // **** How to publish the output?
- // tf (fixed_frame->base_frame),
- // pose message (pose of base frame in the fixed frame)
-
- if (!nh_private_.getParam ("publish_tf", publish_tf_))
- publish_tf_ = true;
- if (!nh_private_.getParam ("publish_pose", publish_pose_))
- publish_pose_ = true;
- if (!nh_private_.getParam ("publish_pose_stamped", publish_pose_stamped_))
- publish_pose_stamped_ = false;
- if (!nh_private_.getParam ("publish_pose_with_covariance", publish_pose_with_covariance_))
- publish_pose_with_covariance_ = false;
- if (!nh_private_.getParam ("publish_pose_with_covariance_stamped", publish_pose_with_covariance_stamped_))
- publish_pose_with_covariance_stamped_ = false;
-
- if (!nh_private_.getParam("position_covariance", position_covariance_))
- {
- position_covariance_.resize(3);
- std::fill(position_covariance_.begin(), position_covariance_.end(), 1e-9);
- }
-
- if (!nh_private_.getParam("orientation_covariance", orientation_covariance_))
- {
- orientation_covariance_.resize(3);
- std::fill(orientation_covariance_.begin(), orientation_covariance_.end(), 1e-9);
- }
- // **** CSM parameters - comments copied from algos.h (by Andrea Censi)
-
- // Maximum angular displacement between scans
- if (!nh_private_.getParam ("max_angular_correction_deg", input_.max_angular_correction_deg))
- input_.max_angular_correction_deg = 45.0;
-
- // Maximum translation between scans (m)
- if (!nh_private_.getParam ("max_linear_correction", input_.max_linear_correction))
- input_.max_linear_correction = 0.50;
-
- // Maximum ICP cycle iterations
- if (!nh_private_.getParam ("max_iterations", input_.max_iterations))
- input_.max_iterations = 10;
-
- // A threshold for stopping (m)
- if (!nh_private_.getParam ("epsilon_xy", input_.epsilon_xy))
- input_.epsilon_xy = 0.000001;
-
- // A threshold for stopping (rad)
- if (!nh_private_.getParam ("epsilon_theta", input_.epsilon_theta))
- input_.epsilon_theta = 0.000001;
-
- // Maximum distance for a correspondence to be valid
- if (!nh_private_.getParam ("max_correspondence_dist", input_.max_correspondence_dist))
- input_.max_correspondence_dist = 0.3;
-
- // Noise in the scan (m)
- if (!nh_private_.getParam ("sigma", input_.sigma))
- input_.sigma = 0.010;
-
- // Use smart tricks for finding correspondences.
- if (!nh_private_.getParam ("use_corr_tricks", input_.use_corr_tricks))
- input_.use_corr_tricks = 1;
-
- // Restart: Restart if error is over threshold
- if (!nh_private_.getParam ("restart", input_.restart))
- input_.restart = 0;
-
- // Restart: Threshold for restarting
- if (!nh_private_.getParam ("restart_threshold_mean_error", input_.restart_threshold_mean_error))
- input_.restart_threshold_mean_error = 0.01;
-
- // Restart: displacement for restarting. (m)
- if (!nh_private_.getParam ("restart_dt", input_.restart_dt))
- input_.restart_dt = 1.0;
-
- // Restart: displacement for restarting. (rad)
- if (!nh_private_.getParam ("restart_dtheta", input_.restart_dtheta))
- input_.restart_dtheta = 0.1;
-
- // Max distance for staying in the same clustering
- if (!nh_private_.getParam ("clustering_threshold", input_.clustering_threshold))
- input_.clustering_threshold = 0.25;
-
- // Number of neighbour rays used to estimate the orientation
- if (!nh_private_.getParam ("orientation_neighbourhood", input_.orientation_neighbourhood))
- input_.orientation_neighbourhood = 20;
-
- // If 0, it's vanilla ICP
- if (!nh_private_.getParam ("use_point_to_line_distance", input_.use_point_to_line_distance))
- input_.use_point_to_line_distance = 1;
-
- // Discard correspondences based on the angles
- if (!nh_private_.getParam ("do_alpha_test", input_.do_alpha_test))
- input_.do_alpha_test = 0;
-
- // Discard correspondences based on the angles - threshold angle, in degrees
- if (!nh_private_.getParam ("do_alpha_test_thresholdDeg", input_.do_alpha_test_thresholdDeg))
- input_.do_alpha_test_thresholdDeg = 20.0;
-
- // Percentage of correspondences to consider: if 0.9,
- // always discard the top 10% of correspondences with more error
- if (!nh_private_.getParam ("outliers_maxPerc", input_.outliers_maxPerc))
- input_.outliers_maxPerc = 0.90;
-
- // Parameters describing a simple adaptive algorithm for discarding.
- // 1) Order the errors.
- // 2) Choose the percentile according to outliers_adaptive_order.
- // (if it is 0.7, get the 70% percentile)
- // 3) Define an adaptive threshold multiplying outliers_adaptive_mult
- // with the value of the error at the chosen percentile.
- // 4) Discard correspondences over the threshold.
- // This is useful to be conservative; yet remove the biggest errors.
- if (!nh_private_.getParam ("outliers_adaptive_order", input_.outliers_adaptive_order))
- input_.outliers_adaptive_order = 0.7;
-
- if (!nh_private_.getParam ("outliers_adaptive_mult", input_.outliers_adaptive_mult))
- input_.outliers_adaptive_mult = 2.0;
-
- // If you already have a guess of the solution, you can compute the polar angle
- // of the points of one scan in the new position. If the polar angle is not a monotone
- // function of the readings index, it means that the surface is not visible in the
- // next position. If it is not visible, then we don't use it for matching.
- if (!nh_private_.getParam ("do_visibility_test", input_.do_visibility_test))
- input_.do_visibility_test = 0;
-
- // no two points in laser_sens can have the same corr.
- if (!nh_private_.getParam ("outliers_remove_doubles", input_.outliers_remove_doubles))
- input_.outliers_remove_doubles = 1;
-
- // If 1, computes the covariance of ICP using the method http://purl.org/censi/2006/icpcov
- if (!nh_private_.getParam ("do_compute_covariance", input_.do_compute_covariance))
- input_.do_compute_covariance = 0;
-
- // Checks that find_correspondences_tricks gives the right answer
- if (!nh_private_.getParam ("debug_verify_tricks", input_.debug_verify_tricks))
- input_.debug_verify_tricks = 0;
-
- // If 1, the field 'true_alpha' (or 'alpha') in the first scan is used to compute the
- // incidence beta, and the factor (1/cos^2(beta)) used to weight the correspondence.");
- if (!nh_private_.getParam ("use_ml_weights", input_.use_ml_weights))
- input_.use_ml_weights = 0;
-
- // If 1, the field 'readings_sigma' in the second scan is used to weight the
- // correspondence by 1/sigma^2
- if (!nh_private_.getParam ("use_sigma_weights", input_.use_sigma_weights))
- input_.use_sigma_weights = 0;
+void LaserScanMatcher::initParams() {
+ init_timer_->cancel();
+ params_.initialize(shared_from_this());
+
+ // static parameters
+ base_frame_ = params_.param("base_frame", std::string("base_link"), "Which frame to use for the robot base");
+ odom_frame_ = params_.param("odom_frame", std::string("odom"), "Which frame to track odometry in");
+ publish_tf_ = params_.param("publish_tf", true, "Whether to publish tf transform from 'odom_frame' to 'base_frame'");
+ use_imu_ = params_.param("use_imu", true, "Whether to use imu messages for predicting the sensor yaw");
+ use_odom_ = params_.param("use_odom", true, "Whether to use odom messages for predicting the sensor pose");
+ use_vel_ = params_.param("use_vel", false, "Whether to use twist messages for predicting the sensor pose");
+ use_tf_ = params_.param("use_tf", false, "Whether to use tf for predicting the sensor pose");
+ stamped_vel_ = params_.param("stamped_vel", false, "Whether to subscribe to stamped twist messages.");
+
+ if (use_tf_ && publish_tf_) {
+ RCLCPP_WARN(get_logger(),"'publish_tf' and 'use_tf' cannot be used together. Disabling TF publishing ...");
+ publish_tf_ = false;
+ }
+
+ // dynamic parameters
+ params_.register_param(&tf_timeout_, "tf_timeout", 0.1, "TF timeout in seconds.", 0.0, 10.0);
+ params_.register_param(&xy_cov_scale_, "xy_cov_scale", 1.0, "Scaling to apply to xy position covariance", 0.0, 1e8);
+ params_.register_param(&xy_cov_offset_, "xy_cov_offset", 0.0, "Offset to apply to xy position covariance", 0.0, 10.0);
+ params_.register_param(&heading_cov_scale_, "heading_cov_scale", 1.0, "Scaling to apply to heading covariance", 0.0, 1e8);
+ params_.register_param(&heading_cov_offset_, "heading_cov_offset", 0.0, "Offset to apply to heading covariance", 0.0, 10.0);
+ params_.register_param(&min_travel_distance_, "min_travel_distance", 0.5, "Distance in meters to trigger a new keyframe", 0.0, 10.0);
+ params_.register_param(&min_travel_heading_, "min_travel_heading", 30.0, "Angle in degrees to trigger a new keyframe.", 0.0, 180.0);
+
+ // CSM parameters - comments copied from algos.h (by Andrea Censi)
+ params_.register_param(&input_.max_angular_correction_deg, "max_angular_correction_deg", 45.0, "Maximum angular displacement between scans.", 0.0, 90.0);
+ params_.register_param(&input_.max_linear_correction, "max_linear_correction", 0.5, "Maximum translation between scans (m).", 0.0, 10.0);
+ params_.register_param(&input_.max_iterations, "max_iterations", 10, "Maximum ICP cycle iterations", 1, 100);
+ params_.register_param(&input_.epsilon_xy, "epsilon_xy", 1e-6, "A threshold for stopping (m).", 1e-10, 1e-1);
+ params_.register_param(&input_.epsilon_theta, "epsilon_theta", 1e-6, "A threshold for stopping (rad).", 1e-10, 1e-1);
+ params_.register_param(&input_.max_correspondence_dist, "max_correspondence_dist", 0.3, "Maximum distance for a correspondence to be valid.", 0.0, 10.0);
+ params_.register_param(&input_.sigma, "sigma", 0.01, "Noise in the scan (m).", 0.0, 1.0);
+ params_.register_param(&input_.use_corr_tricks, "use_corr_tricks", true, "Use smart tricks for finding correspondences.");
+ params_.register_param(&input_.restart, "restart", false, "Restart if error is over threshold.");
+ params_.register_param(&input_.restart_threshold_mean_error, "restart_threshold_mean_error", 0.01, "Threshold for restarting.", 0.0, 1.0);
+ params_.register_param(&input_.restart_dt, "restart_dt", 1.0, "Displacement for restarting. (m).", 0.0, 10.0);
+ params_.register_param(&input_.restart_dtheta, "restart_dtheta", 0.1, "Displacement for restarting. (rad).", 0.0, M_PI_2);
+ params_.register_param(&input_.clustering_threshold, "clustering_threshold", 0.25, "Max distance for staying in the same clustering.", 0.0, 1.0);
+ params_.register_param(&input_.orientation_neighbourhood, "orientation_neighbourhood", 20, "Number of neighbour rays used to estimate the orientation.", 0, 100);
+ params_.register_param(&input_.use_point_to_line_distance, "use_point_to_line_distance", true, "If false, it's vanilla ICP.");
+ params_.register_param(&input_.do_alpha_test, "do_alpha_test", false, "Discard correspondences based on the angles.");
+ params_.register_param(&input_.do_alpha_test_thresholdDeg, "alpha_test_threshold", 20.0, "Threshold angle to discard correspondences, in degrees.", 0.0, 90.0);
+ params_.register_param(&input_.outliers_maxPerc, "outliers_max_perc", 0.9, "Percentage [0, 1] of correspondences to consider with lowest error", 0.0, 1.0);
+ params_.register_param(&input_.outliers_adaptive_order, "outliers_adaptive_order", 0.7, "Percentile [0, 1] to use for adaptive outlier detection", 0.0, 1.0);
+ params_.register_param(&input_.outliers_adaptive_mult, "outliers_adaptive_mult", 2.0, "Threshold multiplier for error at chosen percentile", 0.0, 10.0);
+ params_.register_param(&input_.do_visibility_test, "do_visibility_test", false, "Use visibility test trick for matching.");
+ params_.register_param(&input_.outliers_remove_doubles, "outliers_remove_doubles", true, "Do not allow two different correspondences to share a point");
+ params_.register_param(&input_.do_compute_covariance, "do_compute_covariance", true, "Compute the covariance of the ICP");
+ params_.register_param(&input_.debug_verify_tricks, "debug_verify_tricks", false, "Checks that find_correspondences_tricks gives the right answer.");
+ params_.register_param(&input_.use_ml_weights, "use_ml_weights", false, "Use the 'true_alpha' or 'alpha' field to weight the impact of each correspondence");
+ params_.register_param(&input_.use_sigma_weights, "use_sigma_weights", false, "Use the 'readings_sigma' field of the second scan to weight the correspondence.");
+
+ params_.registerCallback();
}
-void LaserScanMatcher::imuCallback(const sensor_msgs::Imu::ConstPtr& imu_msg)
+void LaserScanMatcher::imuCallback(const sensor_msgs::msg::Imu::SharedPtr imu_msg)
{
- boost::mutex::scoped_lock(mutex_);
- latest_imu_msg_ = *imu_msg;
- if (!received_imu_)
- {
- tf::quaternionMsgToTF(imu_msg->orientation, last_used_imu_orientation_);
- received_imu_ = true;
+ if (!latest_imu_msg_) {
+ tf2::fromMsg(imu_msg->orientation, last_used_imu_orientation_);
}
+ latest_imu_msg_ = imu_msg;
}
-void LaserScanMatcher::odomCallback(const nav_msgs::Odometry::ConstPtr& odom_msg)
+void LaserScanMatcher::odomCallback(const nav_msgs::msg::Odometry::SharedPtr odom_msg)
{
- boost::mutex::scoped_lock(mutex_);
- latest_odom_msg_ = *odom_msg;
- if (!received_odom_)
- {
- tf::poseMsgToTF(odom_msg->pose.pose, last_used_odom_pose_);
- received_odom_ = true;
+ if (!latest_odom_msg_) {
+ tf2::fromMsg(odom_msg->pose.pose, last_used_odom_pose_);
}
+ latest_odom_msg_ = odom_msg;
}
-void LaserScanMatcher::velCallback(const geometry_msgs::Twist::ConstPtr& twist_msg)
+void LaserScanMatcher::velCallback(const geometry_msgs::msg::Twist::SharedPtr twist_msg)
{
- boost::mutex::scoped_lock(mutex_);
- latest_vel_msg_ = *twist_msg;
-
- received_vel_ = true;
+ latest_vel_msg_ = twist_msg;
}
-void LaserScanMatcher::velStmpCallback(const geometry_msgs::TwistStamped::ConstPtr& twist_msg)
+void LaserScanMatcher::velStmpCallback(const geometry_msgs::msg::TwistStamped::SharedPtr twist_msg)
{
- boost::mutex::scoped_lock(mutex_);
- latest_vel_msg_ = twist_msg->twist;
-
- received_vel_ = true;
+ latest_vel_msg_ = std::make_shared(twist_msg->twist);
}
-void LaserScanMatcher::cloudCallback (const PointCloudT::ConstPtr& cloud)
-{
- // **** if first scan, cache the tf from base to the scanner
-
- std_msgs::Header cloud_header = pcl_conversions::fromPCL(cloud->header);
-
- if (!initialized_)
- {
- // cache the static tf from base to laser
- if (!getBaseLaserTransform(cloud_header.frame_id))
- {
- ROS_WARN("Skipping scan");
- return;
- }
-
- PointCloudToLDP(cloud, prev_ldp_scan_);
- last_icp_time_ = cloud_header.stamp;
- initialized_ = true;
- }
-
- LDP curr_ldp_scan;
- PointCloudToLDP(cloud, curr_ldp_scan);
- processScan(curr_ldp_scan, cloud_header.stamp);
-}
-
-void LaserScanMatcher::scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
-{
+void LaserScanMatcher::scanCallback(const sensor_msgs::msg::LaserScan::SharedPtr scan_msg) {
// **** if first scan, cache the tf from base to the scanner
if (!initialized_)
{
createCache(scan_msg); // caches the sin and cos of all angles
- // cache the static transform between the base and laser
- if (!getBaseLaserTransform(scan_msg->header.frame_id))
+ // cache the static tf from base to laser
+ if (!getBaseToLaserTf(scan_msg->header.frame_id))
{
- ROS_WARN("Skipping scan");
return;
}
- laserScanToLDP(scan_msg, prev_ldp_scan_);
+ laserScanToLDP(scan_msg, keyframe_laser_data_);
last_icp_time_ = scan_msg->header.stamp;
initialized_ = true;
}
- LDP curr_ldp_scan;
- laserScanToLDP(scan_msg, curr_ldp_scan);
- processScan(curr_ldp_scan, scan_msg->header.stamp);
+ processScan(scan_msg);
}
-void LaserScanMatcher::processScan(LDP& curr_ldp_scan, const ros::Time& time)
+void LaserScanMatcher::processScan(const sensor_msgs::msg::LaserScan::SharedPtr scan_msg)
{
- ros::WallTime start = ros::WallTime::now();
+ // Canonical Scan Matcher (CSM) is used in the following way:
+ // - The scans are always in the laser frame.
+ // - The reference scan (keyframe_laser_data_) has a pose of [0, 0, 0]
+ // - The new scan (curr_laser_data) has a pose equal to the movement of the
+ // laser in the laser frame since the last scan
+ // - The computed correction is then propagated using the tf machinery
- // CSM is used in the following way:
- // The scans are always in the laser frame
- // The reference scan (prevLDPcan_) has a pose of [0, 0, 0]
- // The new scan (currLDPScan) has a pose equal to the movement
- // of the laser in the laser frame since the last scan
- // The computed correction is then propagated using the tf machinery
+ LDP curr_laser_data;
+ laserScanToLDP(scan_msg, curr_laser_data);
- prev_ldp_scan_->odometry[0] = 0.0;
- prev_ldp_scan_->odometry[1] = 0.0;
- prev_ldp_scan_->odometry[2] = 0.0;
+ keyframe_laser_data_->odometry[0] = 0.0;
+ keyframe_laser_data_->odometry[1] = 0.0;
+ keyframe_laser_data_->odometry[2] = 0.0;
- prev_ldp_scan_->estimate[0] = 0.0;
- prev_ldp_scan_->estimate[1] = 0.0;
- prev_ldp_scan_->estimate[2] = 0.0;
+ keyframe_laser_data_->estimate[0] = 0.0;
+ keyframe_laser_data_->estimate[1] = 0.0;
+ keyframe_laser_data_->estimate[2] = 0.0;
- prev_ldp_scan_->true_pose[0] = 0.0;
- prev_ldp_scan_->true_pose[1] = 0.0;
- prev_ldp_scan_->true_pose[2] = 0.0;
+ keyframe_laser_data_->true_pose[0] = 0.0;
+ keyframe_laser_data_->true_pose[1] = 0.0;
+ keyframe_laser_data_->true_pose[2] = 0.0;
- input_.laser_ref = prev_ldp_scan_;
- input_.laser_sens = curr_ldp_scan;
+ input_.laser_ref = keyframe_laser_data_;
+ input_.laser_sens = curr_laser_data;
+
+ tf2::Transform last_base = last_base_in_fixed_;
// **** estimated change since last scan
// get the predicted offset of the scan base pose from the last scan base pose
- tf::Transform pred_last_base_offset = getPrediction(time);
+ tf2::Transform pred_last_base_offset = getPrediction(scan_msg->header.stamp);
// calculate the predicted scan base pose by applying the predicted offset to the last scan base pose
- tf::Transform pred_base_in_fixed = last_base_in_fixed_ * pred_last_base_offset;
+ tf2::Transform pred_base_in_fixed = last_base_in_fixed_ * pred_last_base_offset;
// calculate the offset between the keyframe base pose and predicted scan base pose
- tf::Transform pred_keyframe_base_offset = keyframe_base_in_fixed_.inverse() * pred_base_in_fixed;
+ tf2::Transform pred_keyframe_base_offset = keyframe_base_in_fixed_.inverse() * pred_base_in_fixed;
// convert the predicted offset from the keyframe base frame to be in the keyframe laser frame
- tf::Transform pred_keyframe_laser_offset = laser_from_base_ * pred_keyframe_base_offset * base_from_laser_ ;
+ tf2::Transform pred_keyframe_laser_offset = laser_from_base_ * pred_keyframe_base_offset * base_from_laser_ ;
input_.first_guess[0] = pred_keyframe_laser_offset.getOrigin().getX();
input_.first_guess[1] = pred_keyframe_laser_offset.getOrigin().getY();
- input_.first_guess[2] = tf::getYaw(pred_keyframe_laser_offset.getRotation());
+ input_.first_guess[2] = tf2::getYaw(pred_keyframe_laser_offset.getRotation());
- // If they are non-Null, free covariance gsl matrices to avoid leaking memory
+ // free covariance matrices, if they are allocated, to avoid leaking memory
if (output_.cov_x_m)
{
gsl_matrix_free(output_.cov_x_m);
- output_.cov_x_m = 0;
+ output_.cov_x_m = nullptr;
}
if (output_.dx_dy1_m)
{
gsl_matrix_free(output_.dx_dy1_m);
- output_.dx_dy1_m = 0;
+ output_.dx_dy1_m = nullptr;
}
if (output_.dx_dy2_m)
{
gsl_matrix_free(output_.dx_dy2_m);
- output_.dx_dy2_m = 0;
+ output_.dx_dy2_m = nullptr;
}
// *** scan match - using point to line icp from CSM
sm_icp(&input_, &output_);
- tf::Transform meas_keyframe_base_offset;
+ tf2::Transform meas_keyframe_base_offset;
if (output_.valid)
{
-
// the measured offset of the scan from the keyframe in the keyframe laser frame
- tf::Transform meas_keyframe_laser_offset;
+ tf2::Transform meas_keyframe_laser_offset;
createTfFromXYTheta(output_.x[0], output_.x[1], output_.x[2], meas_keyframe_laser_offset);
// convert the measured offset from the keyframe laser frame to the keyframe base frame
@@ -519,226 +306,109 @@ void LaserScanMatcher::processScan(LDP& curr_ldp_scan, const ros::Time& time)
xy_cov(0, 1) = gsl_matrix_get(output_.cov_x_m, 0, 1);
xy_cov(1, 0) = gsl_matrix_get(output_.cov_x_m, 1, 0);
xy_cov(1, 1) = gsl_matrix_get(output_.cov_x_m, 1, 1);
- yaw_cov = gsl_matrix_get(output_.cov_x_m, 2, 2);
// rotate xy covariance from the keyframe into odom frame
- auto rotation = getLaserRotation(f2b_kf_);
+ auto rotation = getLaserRotation(keyframe_base_in_fixed_);
xy_cov = rotation * xy_cov * rotation.transpose();
- }
- else {
- xy_cov(0, 0) = position_covariance_[0];
- xy_cov(1, 1) = position_covariance_[1];
- yaw_cov = orientation_covariance_[2];
- }
- if (publish_pose_)
- {
- // unstamped Pose2D message
- geometry_msgs::Pose2D::Ptr pose_msg;
- pose_msg = boost::make_shared();
- pose_msg->x = last_base_in_fixed_.getOrigin().getX();
- pose_msg->y = last_base_in_fixed_.getOrigin().getY();
- pose_msg->theta = tf::getYaw(last_base_in_fixed_.getRotation());
- pose_publisher_.publish(pose_msg);
+ yaw_cov = gsl_matrix_get(output_.cov_x_m, 2, 2);
}
- if (publish_pose_stamped_)
- {
- // stamped Pose message
- geometry_msgs::PoseStamped::Ptr pose_stamped_msg;
- pose_stamped_msg = boost::make_shared();
-
- pose_stamped_msg->header.stamp = time;
- pose_stamped_msg->header.frame_id = fixed_frame_;
-
- tf::poseTFToMsg(last_base_in_fixed_, pose_stamped_msg->pose);
- pose_stamped_publisher_.publish(pose_stamped_msg);
- }
- if (publish_pose_with_covariance_)
- {
- // unstamped PoseWithCovariance message
- geometry_msgs::PoseWithCovariance::Ptr pose_with_covariance_msg;
- pose_with_covariance_msg = boost::make_shared();
- tf::poseTFToMsg(last_base_in_fixed_, pose_with_covariance_msg->pose);
-
- pose_with_covariance_msg->covariance = boost::assign::list_of
- (xy_cov(0, 0)) (xy_cov(0, 1)) (0) (0) (0) (0)
- (xy_cov(1, 0)) (xy_cov(1, 1)) (0) (0) (0) (0)
- (0) (0) (0) (0) (0) (0)
- (0) (0) (0) (0) (0) (0)
- (0) (0) (0) (0) (0) (0)
- (0) (0) (0) (0) (0) (yaw_cov);
-
- pose_with_covariance_publisher_.publish(pose_with_covariance_msg);
- }
- if (publish_pose_with_covariance_stamped_)
- {
+ if (pose_publisher_->get_subscription_count() > 0) {
// stamped Pose message
- geometry_msgs::PoseWithCovarianceStamped::Ptr pose_with_covariance_stamped_msg;
- pose_with_covariance_stamped_msg = boost::make_shared();
-
- pose_with_covariance_stamped_msg->header.stamp = time;
- pose_with_covariance_stamped_msg->header.frame_id = fixed_frame_;
+ geometry_msgs::msg::PoseWithCovarianceStamped pose_msg;
- tf::poseTFToMsg(last_base_in_fixed_, pose_with_covariance_stamped_msg->pose.pose);
+ pose_msg.header.stamp = scan_msg->header.stamp;
+ pose_msg.header.frame_id = odom_frame_;
+ tf2::toMsg(last_base_in_fixed_, pose_msg.pose.pose);
- pose_with_covariance_stamped_msg->pose.covariance = boost::assign::list_of
- (xy_cov(0, 0)) (xy_cov(0, 1)) (0) (0) (0) (0)
- (xy_cov(1, 0)) (xy_cov(1, 1)) (0) (0) (0) (0)
- (0) (0) (0) (0) (0) (0)
- (0) (0) (0) (0) (0) (0)
- (0) (0) (0) (0) (0) (0)
- (0) (0) (0) (0) (0) (yaw_cov);
+ pose_msg.pose.covariance[0] = xy_cov(0, 0) * xy_cov_scale_ + xy_cov_offset_;
+ pose_msg.pose.covariance[1] = xy_cov(0, 1) * xy_cov_scale_;
+ pose_msg.pose.covariance[6] = xy_cov(1, 0) * xy_cov_scale_;
+ pose_msg.pose.covariance[7] = xy_cov(1, 1) * xy_cov_scale_ + xy_cov_offset_;
+ pose_msg.pose.covariance[35] = yaw_cov * heading_cov_scale_ + heading_cov_offset_;
- pose_with_covariance_stamped_publisher_.publish(pose_with_covariance_stamped_msg);
+ pose_publisher_->publish(pose_msg);
}
- if (publish_tf_)
- {
- tf::StampedTransform transform_msg (last_base_in_fixed_, time, fixed_frame_, base_frame_);
- tf_broadcaster_.sendTransform (transform_msg);
+ if (publish_tf_) {
+ geometry_msgs::msg::TransformStamped tf_msg;
+ tf_msg.transform = tf2::toMsg(last_base_in_fixed_);
+
+ tf_msg.header.stamp = scan_msg->header.stamp;;
+ tf_msg.header.frame_id = odom_frame_;
+ tf_msg.child_frame_id = base_frame_;
+ tf_broadcaster_->sendTransform (tf_msg);
}
}
- else
- {
+ else {
meas_keyframe_base_offset.setIdentity();
- ROS_WARN("Error in scan matching");
- }
+ RCLCPP_WARN(get_logger(),"Error in scan matching. Creating new keyframe ...");
+
+ // generate a new keyframe
+ ld_free(keyframe_laser_data_);
+ keyframe_laser_data_ = curr_laser_data;
+ keyframe_base_in_fixed_ = last_base;
+ last_base_in_fixed_ = keyframe_base_in_fixed_;
- // **** swap old and new
+ last_icp_time_ = scan_msg->header.stamp;
+ return;
+ }
if (newKeyframeNeeded(meas_keyframe_base_offset))
{
// generate a keyframe
- ld_free(prev_ldp_scan_);
- prev_ldp_scan_ = curr_ldp_scan;
+ RCLCPP_DEBUG(get_logger(), "Creating new keyframe ...");
+ ld_free(keyframe_laser_data_);
+ keyframe_laser_data_ = curr_laser_data;
keyframe_base_in_fixed_ = last_base_in_fixed_;
}
else
{
- ld_free(curr_ldp_scan);
+ ld_free(curr_laser_data);
}
- last_icp_time_ = time;
-
- // **** statistics
+ last_icp_time_ = scan_msg->header.stamp;
- double dur = (ros::WallTime::now() - start).toSec() * 1e3;
- ROS_DEBUG("Scan matcher total duration: %.1f ms", dur);
+ return;
}
-bool LaserScanMatcher::newKeyframeNeeded(const tf::Transform& d)
-{
- if (fabs(tf::getYaw(d.getRotation())) > kf_dist_angular_) return true;
+bool LaserScanMatcher::newKeyframeNeeded(const tf2::Transform& d) {
+ if (std::fabs(tf2::getYaw(d.getRotation())) > min_travel_heading_ * M_PI / 180.0) {
+ return true;
+ }
double x = d.getOrigin().getX();
double y = d.getOrigin().getY();
- if (x*x + y*y > kf_dist_linear_sq_) return true;
-
- return false;
-}
-
-void LaserScanMatcher::PointCloudToLDP(const PointCloudT::ConstPtr& cloud,
- LDP& ldp)
-{
- double max_d2 = cloud_res_ * cloud_res_;
-
- PointCloudT cloud_f;
-
- cloud_f.points.push_back(cloud->points[0]);
-
- for (unsigned int i = 1; i < cloud->points.size(); ++i)
- {
- const PointT& pa = cloud_f.points[cloud_f.points.size() - 1];
- const PointT& pb = cloud->points[i];
-
- double dx = pa.x - pb.x;
- double dy = pa.y - pb.y;
- double d2 = dx*dx + dy*dy;
-
- if (d2 > max_d2)
- {
- cloud_f.points.push_back(pb);
- }
- }
-
- unsigned int n = cloud_f.points.size();
-
- ldp = ld_alloc_new(n);
-
- for (unsigned int i = 0; i < n; i++)
- {
- // calculate position in laser frame
- if (is_nan(cloud_f.points[i].x) || is_nan(cloud_f.points[i].y))
- {
- ROS_WARN("Laser Scan Matcher: Cloud input contains NaN values. \
- Please use a filtered cloud input.");
- }
- else
- {
- double r = sqrt(cloud_f.points[i].x * cloud_f.points[i].x +
- cloud_f.points[i].y * cloud_f.points[i].y);
-
- if (r > cloud_range_min_ && r < cloud_range_max_)
- {
- ldp->valid[i] = 1;
- ldp->readings[i] = r;
- }
- else
- {
- ldp->valid[i] = 0;
- ldp->readings[i] = -1; // for invalid range
- }
- }
-
- ldp->theta[i] = atan2(cloud_f.points[i].y, cloud_f.points[i].x);
- ldp->cluster[i] = -1;
+ if (x * x + y * y > min_travel_distance_ * min_travel_distance_) {
+ return true;
}
- ldp->min_theta = ldp->theta[0];
- ldp->max_theta = ldp->theta[n-1];
-
- ldp->odometry[0] = 0.0;
- ldp->odometry[1] = 0.0;
- ldp->odometry[2] = 0.0;
-
- ldp->true_pose[0] = 0.0;
- ldp->true_pose[1] = 0.0;
- ldp->true_pose[2] = 0.0;
+ return false;
}
-void LaserScanMatcher::laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& scan_msg,
- LDP& ldp)
-{
- unsigned int n = scan_msg->ranges.size();
+void LaserScanMatcher::laserScanToLDP(const sensor_msgs::msg::LaserScan::SharedPtr& scan, LDP& ldp) {
+ unsigned int n = scan->ranges.size();
ldp = ld_alloc_new(n);
- for (unsigned int i = 0; i < n; i++)
- {
- // calculate position in laser frame
-
- double r = scan_msg->ranges[i];
-
- if (r > scan_msg->range_min && r < scan_msg->range_max)
- {
- // fill in laser scan data
-
+ for (unsigned int i = 0; i < n; i++) {
+ // Calculate position in laser frame
+ double r = scan->ranges[i];
+ if ((r > scan->range_min) && (r < scan->range_max)) {
+ // Fill in laser scan data
ldp->valid[i] = 1;
ldp->readings[i] = r;
}
- else
- {
+ else {
ldp->valid[i] = 0;
ldp->readings[i] = -1; // for invalid range
}
-
- ldp->theta[i] = scan_msg->angle_min + i * scan_msg->angle_increment;
-
- ldp->cluster[i] = -1;
+ ldp->theta[i] = scan->angle_min + i * scan->angle_increment;
+ ldp->cluster[i] = -1;
}
ldp->min_theta = ldp->theta[0];
- ldp->max_theta = ldp->theta[n-1];
+ ldp->max_theta = ldp->theta[n - 1];
ldp->odometry[0] = 0.0;
ldp->odometry[1] = 0.0;
@@ -749,13 +419,11 @@ void LaserScanMatcher::laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& sc
ldp->true_pose[2] = 0.0;
}
-void LaserScanMatcher::createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg)
-{
+void LaserScanMatcher::createCache(const sensor_msgs::msg::LaserScan::SharedPtr& scan_msg) {
a_cos_.clear();
a_sin_.clear();
- for (unsigned int i = 0; i < scan_msg->ranges.size(); ++i)
- {
+ for (unsigned int i = 0; i < scan_msg->ranges.size(); ++i) {
double angle = scan_msg->angle_min + i * scan_msg->angle_increment;
a_cos_.push_back(cos(angle));
a_sin_.push_back(sin(angle));
@@ -765,52 +433,72 @@ void LaserScanMatcher::createCache (const sensor_msgs::LaserScan::ConstPtr& scan
input_.max_reading = scan_msg->range_max;
}
-bool LaserScanMatcher::getBaseLaserTransform(const std::string& frame_id)
-{
- tf::StampedTransform base_from_laser;
- try
- {
- tf_listener_.waitForTransform(base_frame_, frame_id, ros::Time(0), ros::Duration(tf_timeout_));
- tf_listener_.lookupTransform (base_frame_, frame_id, ros::Time(0), base_from_laser);
+bool LaserScanMatcher::getBaseToLaserTf(const std::string& frame_id) {
+ try {
+ auto msg = tf_buffer_->lookupTransform(base_frame_, frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(tf_timeout_));
+ tf2::fromMsg(msg.transform, base_from_laser_);
+ laser_from_base_ = base_from_laser_.inverse();
}
- catch (const tf::TransformException& ex)
- {
- ROS_WARN("Could not get initial transform from base to laser frame, %s", ex.what());
+ catch (tf2::TransformException ex) {
+ RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 2000, "Could not get initial transform of base to laser frame, %s", ex.what());
return false;
}
- base_from_laser_ = base_from_laser;
- laser_from_base_ = base_from_laser_.inverse();
return true;
}
-// returns the predicted offset from the base pose of the last scan
-tf::Transform LaserScanMatcher::getPrediction(const ros::Time& stamp)
+bool LaserScanMatcher::getTfOffset(
+ const std::string& frame_id,
+ const rclcpp::Time& target_stamp,
+ const rclcpp::Time& source_stamp,
+ tf2::Transform& transform)
{
- boost::mutex::scoped_lock(mutex_);
+ if (!tf_buffer_->_frameExists(odom_frame_)) {
+ RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 2000, "tf frame [%s] doesn't exist yet.'", odom_frame_.c_str());
+ return false;
+ }
+
+ if (!tf_buffer_->_frameExists(frame_id)) {
+ RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 2000, "tf frame [%s] doesn't exist yet.'", frame_id.c_str());
+ return false;
+ }
+ try {
+ auto msg = tf_buffer_->lookupTransform(
+ frame_id, target_stamp, frame_id, source_stamp, odom_frame_, rclcpp::Duration::from_seconds(tf_timeout_));
+ tf2::fromMsg(msg.transform, transform);
+ }
+ catch (tf2::TransformException ex) {
+ RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 2000, "Could not get transform: %s", ex.what());
+ return false;
+ }
+
+ return true;
+}
+
+tf2::Transform LaserScanMatcher::getPrediction(const rclcpp::Time& stamp) {
// **** base case - no input available, use zero-motion model
- tf::Transform pred_last_base_offset = tf::Transform::getIdentity();
+ tf2::Transform pred_last_base_offset = tf2::Transform::getIdentity();
// **** use velocity (for example from ab-filter)
if (use_vel_)
{
- double dt = (stamp - last_icp_time_).toSec();
+ double dt = (stamp - last_icp_time_).seconds();
// NOTE: this assumes the velocity is in the base frame and that the base
// and laser frames share the same x,y and z axes
- double pr_ch_x = dt * latest_vel_msg_.linear.x;
- double pr_ch_y = dt * latest_vel_msg_.linear.y;
- double pr_ch_a = dt * latest_vel_msg_.angular.z;
+ double pr_ch_x = dt * latest_vel_msg_->linear.x;
+ double pr_ch_y = dt * latest_vel_msg_->linear.y;
+ double pr_ch_a = dt * latest_vel_msg_->angular.z;
createTfFromXYTheta(pr_ch_x, pr_ch_y, pr_ch_a, pred_last_base_offset);
}
// **** use wheel odometry
- if (use_odom_ && received_odom_)
+ if (use_odom_ && latest_odom_msg_)
{
// NOTE: this assumes the odometry is in the base frame
- tf::Transform latest_odom_pose;
- tf::poseMsgToTF(latest_odom_msg_.pose.pose, latest_odom_pose);
+ tf2::Transform latest_odom_pose;
+ tf2::fromMsg(latest_odom_msg_->pose.pose, latest_odom_pose);
pred_last_base_offset = last_used_odom_pose_.inverse() * latest_odom_pose;
@@ -818,13 +506,13 @@ tf::Transform LaserScanMatcher::getPrediction(const ros::Time& stamp)
}
// **** use imu
- if (use_imu_ && received_imu_)
+ if (use_imu_ && latest_imu_msg_)
{
// NOTE: this assumes the imu is in the base frame
- tf::Quaternion latest_imu_orientation;
- tf::quaternionMsgToTF(latest_imu_msg_.orientation, latest_imu_orientation);
+ tf2::Quaternion latest_imu_orientation;
+ tf2::fromMsg(latest_imu_msg_->orientation, latest_imu_orientation);
- tf::Quaternion imu_orientation_offset = last_used_imu_orientation_.inverse() * latest_imu_orientation;
+ tf2::Quaternion imu_orientation_offset = last_used_imu_orientation_.inverse() * latest_imu_orientation;
pred_last_base_offset.setRotation(imu_orientation_offset);
last_used_imu_orientation_ = latest_imu_orientation;
@@ -833,38 +521,30 @@ tf::Transform LaserScanMatcher::getPrediction(const ros::Time& stamp)
// **** use tf
if (use_tf_)
{
- tf::StampedTransform pred_last_base_offset_tf;
- try
+ tf2::Transform pred_last_base_offset_tf;
+ if (getTfOffset(base_frame_, last_icp_time_, stamp, pred_last_base_offset_tf))
{
- tf_listener_.waitForTransform(base_frame_, last_icp_time_, base_frame_, stamp, fixed_frame_, ros::Duration(tf_timeout_));
- tf_listener_.lookupTransform (base_frame_, last_icp_time_, base_frame_, stamp, fixed_frame_, pred_last_base_offset_tf);
pred_last_base_offset = pred_last_base_offset_tf;
}
- catch (const tf::TransformException& ex)
- {
- ROS_WARN("Could not get base to fixed frame transform, %s", ex.what());
- }
}
return pred_last_base_offset;
}
-void LaserScanMatcher::createTfFromXYTheta(
- double x, double y, double theta, tf::Transform& t)
-{
- t.setOrigin(tf::Vector3(x, y, 0.0));
- tf::Quaternion q;
+void LaserScanMatcher::createTfFromXYTheta(double x, double y, double theta, tf2::Transform& t) {
+ t.setOrigin(tf2::Vector3(x, y, 0.0));
+ tf2::Quaternion q;
q.setRPY(0.0, 0.0, theta);
t.setRotation(q);
}
-Eigen::Matrix2f LaserScanMatcher::getLaserRotation(const tf::Transform& odom_pose) const {
- tf::Transform laser_in_fixed = odom_pose * laser_to_base_;
- tf::Matrix3x3 fixed_from_laser_rot(laser_in_fixed.getRotation());
+Eigen::Matrix2f LaserScanMatcher::getLaserRotation(const tf2::Transform& odom_pose) {
+ tf2::Transform laser_in_fixed = odom_pose * laser_from_base_;
+ tf2::Matrix3x3 fixed_from_laser_rot(laser_in_fixed.getRotation());
double r,p,y;
fixed_from_laser_rot.getRPY(r, p, y);
Eigen::Rotation2Df t(y);
return t.toRotationMatrix();
}
-} // namespace scan_tools
+} // namespace scan_tools
diff --git a/laser_scan_matcher/src/laser_scan_matcher_node.cpp b/laser_scan_matcher/src/laser_scan_matcher_node.cpp
index 58d1b6a..2639402 100644
--- a/laser_scan_matcher/src/laser_scan_matcher_node.cpp
+++ b/laser_scan_matcher/src/laser_scan_matcher_node.cpp
@@ -36,13 +36,14 @@
*/
#include
+#include
int main(int argc, char** argv)
{
- ros::init(argc, argv, "LaserScanMatcher");
- ros::NodeHandle nh;
- ros::NodeHandle nh_private("~");
- scan_tools::LaserScanMatcher laser_scan_matcher(nh, nh_private);
- ros::spin();
+ rclcpp::init(argc, argv);
+ auto node = std::make_shared();
+ rclcpp::spin(node->get_node_base_interface());
+ rclcpp::shutdown();
+
return 0;
}
diff --git a/laser_scan_matcher/src/laser_scan_matcher_nodelet.cpp b/laser_scan_matcher/src/laser_scan_matcher_nodelet.cpp
deleted file mode 100644
index 9fc4684..0000000
--- a/laser_scan_matcher/src/laser_scan_matcher_nodelet.cpp
+++ /dev/null
@@ -1,55 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-/* This package uses Canonical Scan Matcher [1], written by
- * Andrea Censi
- *
- * [1] A. Censi, "An ICP variant using a point-to-line metric"
- * Proceedings of the IEEE International Conference
- * on Robotics and Automation (ICRA), 2008
- */
-
-#include
-
-typedef scan_tools::LaserScanMatcherNodelet LaserScanMatcherNodelet;
-
-PLUGINLIB_EXPORT_CLASS(LaserScanMatcherNodelet, nodelet::Nodelet)
-
-void LaserScanMatcherNodelet::onInit()
-{
- NODELET_INFO("Initializing LaserScanMatcher Nodelet");
-
- // TODO: Do we want the single threaded or multithreaded NH?
- ros::NodeHandle nh = getMTNodeHandle();
- ros::NodeHandle nh_private = getMTPrivateNodeHandle();
-
- scan_matcher_ = boost::shared_ptr(
- new LaserScanMatcher(nh, nh_private));
-}
-
diff --git a/laser_scan_matcher/src/param_handler.cpp b/laser_scan_matcher/src/param_handler.cpp
new file mode 100644
index 0000000..275ba1b
--- /dev/null
+++ b/laser_scan_matcher/src/param_handler.cpp
@@ -0,0 +1,106 @@
+#include
+
+namespace scan_tools {
+
+void ParamHandler::initialize(rclcpp::Node::SharedPtr node) {
+ node_ = node;
+}
+
+void ParamHandler::registerCallback() {
+ params_callback_handle_ = node_->add_on_set_parameters_callback(
+ std::bind(&ParamHandler::parametersCallback, this, std::placeholders::_1));
+}
+
+rcl_interfaces::msg::SetParametersResult ParamHandler::parametersCallback(
+ const std::vector ¶meters)
+{
+ rcl_interfaces::msg::SetParametersResult result;
+ result.successful = true;
+ result.reason = "success";
+
+ for (const auto ¶m: parameters) {
+ if (param.get_type() == rclcpp::ParameterType::PARAMETER_BOOL) {
+ auto bool_param = bool_params_.find(param.get_name());
+ if (bool_param != bool_params_.end()) {
+ *bool_param->second = param.as_bool();
+ RCLCPP_INFO(node_->get_logger(), "Parameter updated: %s = %s", param.get_name().c_str(), (param.as_bool() ? "true": "false"));
+ }
+ else {
+ auto int_param = int_params_.find(param.get_name());
+ if (int_param != int_params_.end()) {
+ *int_param->second = param.as_bool();
+ RCLCPP_INFO(node_->get_logger(), "Parameter updated: %s = %s", param.get_name().c_str(), (param.as_bool() ? "true": "false"));
+ }
+ RCLCPP_WARN(node_->get_logger(), "Unknown bool parameter updated: %s", param.get_name().c_str());
+ }
+ }
+ else if (param.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE) {
+ auto double_param = double_params_.find(param.get_name());
+ if (double_param != double_params_.end()) {
+ *double_param->second = param.as_double();
+ RCLCPP_INFO(node_->get_logger(), "Parameter updated: %s = %lf", param.get_name().c_str(), param.as_double());
+ }
+ else {
+ RCLCPP_WARN(node_->get_logger(), "Unknown double parameter updated: %s", param.get_name().c_str());
+ }
+ }
+ else if (param.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER) {
+ auto int_param = int_params_.find(param.get_name());
+ if (int_param != int_params_.end()) {
+ *int_param->second = param.as_int();
+ RCLCPP_INFO(node_->get_logger(), "Parameter updated: %s = %ld", param.get_name().c_str(), param.as_int());
+ }
+ else {
+ RCLCPP_WARN(node_->get_logger(), "Unknown int parameter updated: %s", param.get_name().c_str());
+ }
+ }
+ else {
+ RCLCPP_WARN(node_->get_logger(), "Unsupported parameter type updated: %s (%s)", param.get_name().c_str(), param.get_type_name().c_str());
+ }
+ }
+
+ return result;
+}
+
+void ParamHandler::register_param(
+ int* param, const std::string& name, bool default_val, const std::string& description)
+{
+ auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
+ descriptor.description = description;
+ descriptor.read_only = false;
+ node_->declare_parameter(name, rclcpp::ParameterValue(default_val), descriptor);
+ *param = node_->get_parameter(name).as_bool();
+ int_params_[name] = param;
+}
+
+void ParamHandler::register_param(
+ int* param, const std::string& name, int default_val, const std::string& description, int min, int max)
+{
+ auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
+ descriptor.description = description;
+ descriptor.read_only = false;
+ descriptor.integer_range.resize(1);
+ descriptor.integer_range[0].from_value = min;
+ descriptor.integer_range[0].to_value = max;
+ descriptor.integer_range[0].step = 0;
+ node_->declare_parameter(name, default_val, descriptor);
+ *param = node_->get_parameter(name).as_int();
+ int_params_[name] = param;
+}
+
+void ParamHandler::register_param(
+ double* param, const std::string& name, double default_val, const std::string& description, double min, double max)
+{
+ auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
+ descriptor.description = description;
+ descriptor.read_only = false;
+ descriptor.floating_point_range.resize(1);
+ descriptor.floating_point_range[0].from_value = min;
+ descriptor.floating_point_range[0].to_value = max;
+ descriptor.floating_point_range[0].step = 0;
+ node_->declare_parameter(name, default_val, descriptor);
+ *param = node_->get_parameter(name).as_double();
+ double_params_[name] = param;
+}
+
+} // namespace scan_tools
diff --git a/laser_scan_matcher/test/covariance.test b/laser_scan_matcher/test/covariance.test
deleted file mode 100644
index 5108be3..0000000
--- a/laser_scan_matcher/test/covariance.test
+++ /dev/null
@@ -1,22 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/laser_scan_matcher/test/run.test b/laser_scan_matcher/test/run.test
deleted file mode 100644
index a6dbf8d..0000000
--- a/laser_scan_matcher/test/run.test
+++ /dev/null
@@ -1,13 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/laser_scan_sparsifier/CHANGELOG.rst b/laser_scan_sparsifier/CHANGELOG.rst
deleted file mode 100644
index 24f4b9f..0000000
--- a/laser_scan_sparsifier/CHANGELOG.rst
+++ /dev/null
@@ -1,22 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package laser_scan_sparsifier
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-
-0.3.3 (2021-02-15)
-------------------
-* update to use non deprecated pluginlib macro
-
-0.3.2 (2016-03-19)
-------------------
-
-0.3.1 (2015-12-18)
-------------------
-
-0.3.0 (2015-11-10)
-------------------
-
-0.2.1 (2015-10-14)
-------------------
-* [sys] Catkinizing: laser_scan_sparsifier
-* [sys] renamed skip to step parameter in scan sparsifier
-* Contributors: Ivan Dryanovski, Miguel Sarabia
diff --git a/laser_scan_sparsifier/CMakeLists.txt b/laser_scan_sparsifier/CMakeLists.txt
deleted file mode 100644
index 059f28b..0000000
--- a/laser_scan_sparsifier/CMakeLists.txt
+++ /dev/null
@@ -1,56 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(laser_scan_sparsifier)
-
-# List C++ dependencies on ros packages
-set( ROS_CXX_DEPENDENCIES
- roscpp
- nodelet
- sensor_msgs)
-
-# Find catkin and all required ROS components
-find_package(catkin REQUIRED COMPONENTS ${ROS_CXX_DEPENDENCIES})
-
-# Set include directories
-include_directories(include ${catkin_INCLUDE_DIRS})
-
-# Declare info that other packages need to import library generated here
-catkin_package(
- INCLUDE_DIRS include
- LIBRARIES laser_scan_sparsifier
- CATKIN_DEPENDS ${ROS_CXX_DEPENDENCIES}
-)
-
-#Create library
-add_library(laser_scan_sparsifier src/laser_scan_sparsifier.cpp)
-target_link_libraries( laser_scan_sparsifier ${catkin_LIBRARIES})
-add_dependencies(laser_scan_sparsifier ${catkin_EXPORTED_TARGETS})
-
-#Create nodelet
-add_library(laser_scan_sparsifier_nodelet src/laser_scan_sparsifier_nodelet.cpp)
-target_link_libraries(laser_scan_sparsifier_nodelet laser_scan_sparsifier)
-
-#Create node
-add_executable(laser_scan_sparsifier_node src/laser_scan_sparsifier_node.cpp)
-target_link_libraries( laser_scan_sparsifier_node laser_scan_sparsifier )
-
-#Install library
-install(TARGETS laser_scan_sparsifier laser_scan_sparsifier_nodelet
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
-
-#Install library includes
-install(DIRECTORY include/laser_scan_sparsifier/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} )
-
-#Install node
-install(TARGETS laser_scan_sparsifier_node
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} )
-
-#Install nodelet description
-install(FILES laser_scan_sparsifier_nodelet.xml
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
-
-#Install demo directory
-install(DIRECTORY demo
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
diff --git a/laser_scan_sparsifier/demo/demo.bag b/laser_scan_sparsifier/demo/demo.bag
deleted file mode 100644
index 90ba77e..0000000
Binary files a/laser_scan_sparsifier/demo/demo.bag and /dev/null differ
diff --git a/laser_scan_sparsifier/demo/demo.launch b/laser_scan_sparsifier/demo/demo.launch
deleted file mode 100644
index e2c7d1e..0000000
--- a/laser_scan_sparsifier/demo/demo.launch
+++ /dev/null
@@ -1,12 +0,0 @@
-
-
-
-
-
-
-
-
-
-
diff --git a/laser_scan_sparsifier/demo/demo.vcg b/laser_scan_sparsifier/demo/demo.vcg
deleted file mode 100644
index db43ce5..0000000
--- a/laser_scan_sparsifier/demo/demo.vcg
+++ /dev/null
@@ -1,93 +0,0 @@
-Background\ ColorR=0
-Background\ ColorG=0
-Background\ ColorB=0
-Fixed\ Frame=/laser
-Target\ Frame=
-Grid.Alpha=0.5
-Grid.Cell\ Size=1
-Grid.ColorR=0.5
-Grid.ColorG=0.5
-Grid.ColorB=0.5
-Grid.Enabled=1
-Grid.Line\ Style=0
-Grid.Line\ Width=0.03
-Grid.Normal\ Cell\ Count=0
-Grid.OffsetX=0
-Grid.OffsetY=0
-Grid.OffsetZ=0
-Grid.Plane=0
-Grid.Plane\ Cell\ Count=10
-Grid.Reference\ Frame=
-Laser\ Scan\ In.Alpha=0.1
-Laser\ Scan\ In.Billboard\ Size=0.02
-Laser\ Scan\ In.Color\ Transformer=Flat Color
-Laser\ Scan\ In.Decay\ Time=0
-Laser\ Scan\ In.Enabled=1
-Laser\ Scan\ In.Position\ Transformer=XYZ
-Laser\ Scan\ In.Selectable=1
-Laser\ Scan\ In.Style=1
-Laser\ Scan\ In.Topic=/scan
-Laser\ Scan\ In..AxisAutocompute\ Value\ Bounds=1
-Laser\ Scan\ In..AxisAxis=2
-Laser\ Scan\ In..AxisMax\ Value=8.6725e-08
-Laser\ Scan\ In..AxisMin\ Value=-1.09645e-07
-Laser\ Scan\ In..AxisUse\ Fixed\ Frame=1
-Laser\ Scan\ In..Flat\ ColorColorR=0.0431373
-Laser\ Scan\ In..Flat\ ColorColorG=1
-Laser\ Scan\ In..Flat\ ColorColorB=0
-Laser\ Scan\ In..IntensityAutocompute\ Intensity\ Bounds=1
-Laser\ Scan\ In..IntensityChannel\ Name=intensity
-Laser\ Scan\ In..IntensityMax\ ColorR=1
-Laser\ Scan\ In..IntensityMax\ ColorG=1
-Laser\ Scan\ In..IntensityMax\ ColorB=1
-Laser\ Scan\ In..IntensityMax\ Intensity=4096
-Laser\ Scan\ In..IntensityMin\ ColorR=0
-Laser\ Scan\ In..IntensityMin\ ColorG=0
-Laser\ Scan\ In..IntensityMin\ ColorB=0
-Laser\ Scan\ In..IntensityMin\ Intensity=0
-Laser\ Scan\ In..IntensityUse\ full\ RGB\ spectrum=0
-Laser\ Scan\ Out.Alpha=1
-Laser\ Scan\ Out.Billboard\ Size=0.03
-Laser\ Scan\ Out.Color\ Transformer=Flat Color
-Laser\ Scan\ Out.Decay\ Time=0
-Laser\ Scan\ Out.Enabled=1
-Laser\ Scan\ Out.Position\ Transformer=XYZ
-Laser\ Scan\ Out.Selectable=1
-Laser\ Scan\ Out.Style=1
-Laser\ Scan\ Out.Topic=/scan_sparse
-Laser\ Scan\ Out..AxisAutocompute\ Value\ Bounds=1
-Laser\ Scan\ Out..AxisAxis=2
-Laser\ Scan\ Out..AxisMax\ Value=10
-Laser\ Scan\ Out..AxisMin\ Value=-10
-Laser\ Scan\ Out..AxisUse\ Fixed\ Frame=1
-Laser\ Scan\ Out..Flat\ ColorColorR=1
-Laser\ Scan\ Out..Flat\ ColorColorG=0
-Laser\ Scan\ Out..Flat\ ColorColorB=0
-Laser\ Scan\ Out..IntensityAutocompute\ Intensity\ Bounds=1
-Laser\ Scan\ Out..IntensityChannel\ Name=intensity
-Laser\ Scan\ Out..IntensityMax\ ColorR=1
-Laser\ Scan\ Out..IntensityMax\ ColorG=1
-Laser\ Scan\ Out..IntensityMax\ ColorB=1
-Laser\ Scan\ Out..IntensityMax\ Intensity=4096
-Laser\ Scan\ Out..IntensityMin\ ColorR=0
-Laser\ Scan\ Out..IntensityMin\ ColorG=0
-Laser\ Scan\ Out..IntensityMin\ ColorB=0
-Laser\ Scan\ Out..IntensityMin\ Intensity=0
-Laser\ Scan\ Out..IntensityUse\ full\ RGB\ spectrum=0
-Tool\ 2D\ Nav\ GoalTopic=goal
-Tool\ 2D\ Pose\ EstimateTopic=initialpose
-Camera\ Type=rviz::OrbitViewController
-Camera\ Config=0.621 1.57915 11.0056 0.281448 0.0839437 -0.509401
-Property\ Grid\ State=selection=Laser Scan In.Enabled.Laser Scan In.Alpha;expanded=.Global Options,Laser Scan In.Enabled,Laser Scan Out.Enabled;scrollpos=0,0;splitterpos=133,266;ispageselected=1
-[Display0]
-Name=Grid
-Package=rviz
-ClassName=rviz::GridDisplay
-[Display1]
-Name=Laser Scan In
-Package=rviz
-ClassName=rviz::LaserScanDisplay
-[Display2]
-Name=Laser Scan Out
-Package=rviz
-ClassName=rviz::LaserScanDisplay
diff --git a/laser_scan_sparsifier/include/laser_scan_sparsifier/laser_scan_sparsifier.h b/laser_scan_sparsifier/include/laser_scan_sparsifier/laser_scan_sparsifier.h
deleted file mode 100644
index 7437f0a..0000000
--- a/laser_scan_sparsifier/include/laser_scan_sparsifier/laser_scan_sparsifier.h
+++ /dev/null
@@ -1,64 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef LASER_SCAN_SPARSIFIER_LASER_SCAN_SPARSIFIER_H
-#define LASER_SCAN_SPARSIFIER_LASER_SCAN_SPARSIFIER_H
-
-#include
-#include
-
-namespace scan_tools {
-
-class LaserScanSparsifier
-{
- public:
-
- LaserScanSparsifier(ros::NodeHandle nh, ros::NodeHandle nh_private);
- virtual ~LaserScanSparsifier();
-
- private:
-
- // **** ROS-related
- ros::NodeHandle nh_;
- ros::NodeHandle nh_private_;
- ros::Subscriber scan_subscriber_;
- ros::Publisher scan_publisher_;
-
- // **** paramaters
-
- int step_;
-
- // **** member functions
-
- void scanCallback(const sensor_msgs::LaserScanConstPtr& scan_msg);
-};
-
-} //namespace scan_tools
-
-#endif // LASER_SCAN_SPARSIFIER_LASER_SCAN_SPARSIFIER_H
diff --git a/laser_scan_sparsifier/include/laser_scan_sparsifier/laser_scan_sparsifier_nodelet.h b/laser_scan_sparsifier/include/laser_scan_sparsifier/laser_scan_sparsifier_nodelet.h
deleted file mode 100644
index 49c3722..0000000
--- a/laser_scan_sparsifier/include/laser_scan_sparsifier/laser_scan_sparsifier_nodelet.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef LASER_SCAN_SPARSIFIER_LASER_SCAN_SPARSIFIER_NODELET_H
-#define LASER_SCAN_SPARSIFIER_LASER_SCAN_SPARSIFIER_NODELET_H
-
-#include
-#include
-
-#include "laser_scan_sparsifier/laser_scan_sparsifier.h"
-
-namespace scan_tools {
-
-class LaserScanSparsifierNodelet : public nodelet::Nodelet
-{
- public:
- virtual void onInit();
-
- private:
- LaserScanSparsifier * laser_scan_sparsifier_; // FIXME: change to smart pointer
-};
-
-} //namespace scan_tools
-
-#endif // LASER_SCAN_SPARSIFIER_LASER_SCAN_SPARSIFIER_NODELET_H
diff --git a/laser_scan_sparsifier/laser_scan_sparsifier_nodelet.xml b/laser_scan_sparsifier/laser_scan_sparsifier_nodelet.xml
deleted file mode 100644
index 9c76adc..0000000
--- a/laser_scan_sparsifier/laser_scan_sparsifier_nodelet.xml
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
-
- Laser scan sparsifier nodelet publisher.
-
-
-
diff --git a/laser_scan_sparsifier/package.xml b/laser_scan_sparsifier/package.xml
deleted file mode 100644
index b2676e5..0000000
--- a/laser_scan_sparsifier/package.xml
+++ /dev/null
@@ -1,30 +0,0 @@
-
- laser_scan_sparsifier
- 0.3.3
-
- The laser_scan_sparsifier takes in a LaserScan message and sparsifies it.
-
- Ivan Dryanovski
- Carlos
-
- http://wiki.ros.org/laser_scan_matcher
- Ivan Dryanovski
- William Morris
-
- BSD
-
- catkin
-
- roscpp
- nodelet
- sensor_msgs
-
- roscpp
- nodelet
- sensor_msgs
-
-
-
-
-
-
diff --git a/laser_scan_sparsifier/src/laser_scan_sparsifier.cpp b/laser_scan_sparsifier/src/laser_scan_sparsifier.cpp
deleted file mode 100644
index f25c184..0000000
--- a/laser_scan_sparsifier/src/laser_scan_sparsifier.cpp
+++ /dev/null
@@ -1,99 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_scan_sparsifier/laser_scan_sparsifier.h"
-
-namespace scan_tools {
-
-LaserScanSparsifier::LaserScanSparsifier(ros::NodeHandle nh, ros::NodeHandle nh_private):
- nh_(nh),
- nh_private_(nh_private)
-{
- ROS_INFO ("Starting LaserScanSparsifier");
-
- // **** get paramters
-
- if (!nh_private_.getParam ("step", step_))
- step_ = 2;
-
- ROS_ASSERT_MSG(step_ > 0,
- "step parameter is set to %, must be > 0", step_);
-
- // **** advertise topics
-
- scan_publisher_ = nh_.advertise(
- "scan_sparse", 10);
-
- // **** subscribe to laser scan messages
-
- scan_subscriber_ = nh_.subscribe(
- "scan", 10, &LaserScanSparsifier::scanCallback, this);
-}
-
-LaserScanSparsifier::~LaserScanSparsifier ()
-{
- ROS_INFO ("Destroying LaserScanSparsifier");
-}
-
-void LaserScanSparsifier::scanCallback (const sensor_msgs::LaserScanConstPtr& scan_msg)
-{
- sensor_msgs::LaserScan::Ptr scan_sparse;
- scan_sparse = boost::make_shared();
-
- // copy over equal fields
-
- scan_sparse->header = scan_msg->header;
- scan_sparse->range_min = scan_msg->range_min;
- scan_sparse->range_max = scan_msg->range_max;
- scan_sparse->angle_min = scan_msg->angle_min;
- scan_sparse->angle_increment = scan_msg->angle_increment * step_;
- scan_sparse->time_increment = scan_msg->time_increment;
- scan_sparse->scan_time = scan_msg->scan_time;
-
- // determine size of new scan
-
- unsigned int size_sparse = scan_msg->ranges.size() / step_;
- scan_sparse->ranges.resize(size_sparse);
-
- // determine new maximum angle
-
- scan_sparse->angle_max =
- scan_sparse->angle_min + (scan_sparse->angle_increment * (size_sparse - 1));
-
- for (unsigned int i = 0; i < size_sparse; i++)
- {
- scan_sparse->ranges[i] = scan_msg->ranges[i * step_];
- // TODO - also copy intensity values
- }
-
- scan_publisher_.publish(scan_sparse);
-}
-
-} //namespace scan_tools
-
diff --git a/laser_scan_sparsifier/src/laser_scan_sparsifier_node.cpp b/laser_scan_sparsifier/src/laser_scan_sparsifier_node.cpp
deleted file mode 100644
index d408ad7..0000000
--- a/laser_scan_sparsifier/src/laser_scan_sparsifier_node.cpp
+++ /dev/null
@@ -1,40 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_scan_sparsifier/laser_scan_sparsifier.h"
-
-int main (int argc, char **argv)
-{
- ros::init (argc, argv, "LaserScanSparsifier");
- ros::NodeHandle nh;
- ros::NodeHandle nh_private("~");
- scan_tools::LaserScanSparsifier laser_scan_sparsifier(nh, nh_private);
- ros::spin ();
- return 0;
-}
diff --git a/laser_scan_sparsifier/src/laser_scan_sparsifier_nodelet.cpp b/laser_scan_sparsifier/src/laser_scan_sparsifier_nodelet.cpp
deleted file mode 100644
index 1fc4bad..0000000
--- a/laser_scan_sparsifier/src/laser_scan_sparsifier_nodelet.cpp
+++ /dev/null
@@ -1,45 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_scan_sparsifier/laser_scan_sparsifier_nodelet.h"
-
-typedef scan_tools::LaserScanSparsifierNodelet LaserScanSparsifierNodelet;
-
-PLUGINLIB_EXPORT_CLASS(LaserScanSparsifierNodelet, nodelet::Nodelet)
-
-void LaserScanSparsifierNodelet::onInit ()
-{
- NODELET_INFO("Initializing LaserScanSparsifier Nodelet");
-
- // TODO: Do we want the single threaded or multithreaded NH?
- ros::NodeHandle nh = getMTNodeHandle();
- ros::NodeHandle nh_private = getMTPrivateNodeHandle();
-
- laser_scan_sparsifier_ = new LaserScanSparsifier(nh, nh_private);
-}
diff --git a/laser_scan_splitter/CHANGELOG.rst b/laser_scan_splitter/CHANGELOG.rst
deleted file mode 100644
index 4105225..0000000
--- a/laser_scan_splitter/CHANGELOG.rst
+++ /dev/null
@@ -1,21 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package laser_scan_splitter
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-
-0.3.3 (2021-02-15)
-------------------
-* update to use non deprecated pluginlib macro
-
-0.3.2 (2016-03-19)
-------------------
-
-0.3.1 (2015-12-18)
-------------------
-
-0.3.0 (2015-11-10)
-------------------
-
-0.2.1 (2015-10-14)
-------------------
-* [sys] Catkinization: laser_scan_splitter
-* Contributors: Ivan Dryanovski, Miguel Sarabia
diff --git a/laser_scan_splitter/CMakeLists.txt b/laser_scan_splitter/CMakeLists.txt
deleted file mode 100644
index 7de4faf..0000000
--- a/laser_scan_splitter/CMakeLists.txt
+++ /dev/null
@@ -1,56 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(laser_scan_splitter)
-
-# List C++ dependencies on ros packages
-set( ROS_CXX_DEPENDENCIES
- roscpp
- nodelet
- sensor_msgs)
-
-# Find catkin and all required ROS components
-find_package(catkin REQUIRED COMPONENTS ${ROS_CXX_DEPENDENCIES})
-
-# Set include directories
-include_directories(include ${catkin_INCLUDE_DIRS})
-
-# Declare info that other packages need to import library generated here
-catkin_package(
- INCLUDE_DIRS include
- LIBRARIES laser_scan_splitter
- CATKIN_DEPENDS ${ROS_CXX_DEPENDENCIES}
-)
-
-#Create library
-add_library(laser_scan_splitter src/laser_scan_splitter.cpp)
-target_link_libraries( laser_scan_splitter ${catkin_LIBRARIES})
-add_dependencies(laser_scan_splitter ${catkin_EXPORTED_TARGETS})
-
-#Create nodelet
-add_library(laser_scan_splitter_nodelet src/laser_scan_splitter_nodelet.cpp)
-target_link_libraries(laser_scan_splitter_nodelet laser_scan_splitter)
-
-#Create node
-add_executable(laser_scan_splitter_node src/laser_scan_splitter_node.cpp)
-target_link_libraries( laser_scan_splitter_node laser_scan_splitter )
-
-#Install library
-install(TARGETS laser_scan_splitter laser_scan_splitter_nodelet
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
-
-#Install library includes
-install(DIRECTORY include/laser_scan_splitter/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} )
-
-#Install node
-install(TARGETS laser_scan_splitter_node
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} )
-
-#Install nodelet description
-install(FILES laser_scan_splitter_nodelet.xml
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
-
-#Install demo directory
-install(DIRECTORY demo
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
diff --git a/laser_scan_splitter/demo/demo.bag b/laser_scan_splitter/demo/demo.bag
deleted file mode 100644
index 90ba77e..0000000
Binary files a/laser_scan_splitter/demo/demo.bag and /dev/null differ
diff --git a/laser_scan_splitter/demo/demo.launch b/laser_scan_splitter/demo/demo.launch
deleted file mode 100644
index 4e268fc..0000000
--- a/laser_scan_splitter/demo/demo.launch
+++ /dev/null
@@ -1,14 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/laser_scan_splitter/demo/demo.vcg b/laser_scan_splitter/demo/demo.vcg
deleted file mode 100644
index 503af9b..0000000
--- a/laser_scan_splitter/demo/demo.vcg
+++ /dev/null
@@ -1,149 +0,0 @@
-Background\ ColorR=0
-Background\ ColorG=0
-Background\ ColorB=0
-Fixed\ Frame=/laser
-Target\ Frame=
-Grid.Alpha=0.5
-Grid.Cell\ Size=1
-Grid.ColorR=0.5
-Grid.ColorG=0.5
-Grid.ColorB=0.5
-Grid.Enabled=1
-Grid.Line\ Style=0
-Grid.Line\ Width=0.03
-Grid.Normal\ Cell\ Count=0
-Grid.OffsetX=0
-Grid.OffsetY=0
-Grid.OffsetZ=0
-Grid.Plane=0
-Grid.Plane\ Cell\ Count=10
-Grid.Reference\ Frame=
-Laser\ Scan\ 1.Alpha=1
-Laser\ Scan\ 1.Billboard\ Size=0.01
-Laser\ Scan\ 1.Color\ Transformer=Flat Color
-Laser\ Scan\ 1.Decay\ Time=0
-Laser\ Scan\ 1.Enabled=1
-Laser\ Scan\ 1.Position\ Transformer=XYZ
-Laser\ Scan\ 1.Selectable=1
-Laser\ Scan\ 1.Style=0
-Laser\ Scan\ 1.Topic=scan1
-Laser\ Scan\ 1..AxisAutocompute\ Value\ Bounds=1
-Laser\ Scan\ 1..AxisAxis=2
-Laser\ Scan\ 1..AxisMax\ Value=10
-Laser\ Scan\ 1..AxisMin\ Value=-10
-Laser\ Scan\ 1..AxisUse\ Fixed\ Frame=1
-Laser\ Scan\ 1..Flat\ ColorColorR=1
-Laser\ Scan\ 1..Flat\ ColorColorG=0
-Laser\ Scan\ 1..Flat\ ColorColorB=0
-Laser\ Scan\ 1..IntensityAutocompute\ Intensity\ Bounds=1
-Laser\ Scan\ 1..IntensityMax\ ColorR=1
-Laser\ Scan\ 1..IntensityMax\ ColorG=1
-Laser\ Scan\ 1..IntensityMax\ ColorB=1
-Laser\ Scan\ 1..IntensityMax\ Intensity=4096
-Laser\ Scan\ 1..IntensityMin\ ColorR=0
-Laser\ Scan\ 1..IntensityMin\ ColorG=0
-Laser\ Scan\ 1..IntensityMin\ ColorB=0
-Laser\ Scan\ 1..IntensityMin\ Intensity=0
-Laser\ Scan\ 2.Alpha=1
-Laser\ Scan\ 2.Billboard\ Size=0.01
-Laser\ Scan\ 2.Color\ Transformer=Flat Color
-Laser\ Scan\ 2.Decay\ Time=0
-Laser\ Scan\ 2.Enabled=1
-Laser\ Scan\ 2.Position\ Transformer=XYZ
-Laser\ Scan\ 2.Selectable=1
-Laser\ Scan\ 2.Style=0
-Laser\ Scan\ 2.Topic=scan2
-Laser\ Scan\ 2..AxisAutocompute\ Value\ Bounds=1
-Laser\ Scan\ 2..AxisAxis=2
-Laser\ Scan\ 2..AxisMax\ Value=10
-Laser\ Scan\ 2..AxisMin\ Value=-10
-Laser\ Scan\ 2..AxisUse\ Fixed\ Frame=1
-Laser\ Scan\ 2..Flat\ ColorColorR=0
-Laser\ Scan\ 2..Flat\ ColorColorG=1
-Laser\ Scan\ 2..Flat\ ColorColorB=0
-Laser\ Scan\ 2..IntensityAutocompute\ Intensity\ Bounds=1
-Laser\ Scan\ 2..IntensityMax\ ColorR=1
-Laser\ Scan\ 2..IntensityMax\ ColorG=1
-Laser\ Scan\ 2..IntensityMax\ ColorB=1
-Laser\ Scan\ 2..IntensityMax\ Intensity=4096
-Laser\ Scan\ 2..IntensityMin\ ColorR=0
-Laser\ Scan\ 2..IntensityMin\ ColorG=0
-Laser\ Scan\ 2..IntensityMin\ ColorB=0
-Laser\ Scan\ 2..IntensityMin\ Intensity=0
-Laser\ Scan\ In.Alpha=1
-Laser\ Scan\ In.Billboard\ Size=0.01
-Laser\ Scan\ In.Color\ Transformer=Flat Color
-Laser\ Scan\ In.Decay\ Time=0
-Laser\ Scan\ In.Enabled=0
-Laser\ Scan\ In.Position\ Transformer=XYZ
-Laser\ Scan\ In.Selectable=1
-Laser\ Scan\ In.Style=0
-Laser\ Scan\ In.Topic=/scan
-Laser\ Scan\ In..AxisAutocompute\ Value\ Bounds=1
-Laser\ Scan\ In..AxisAxis=2
-Laser\ Scan\ In..AxisMax\ Value=8.6725e-08
-Laser\ Scan\ In..AxisMin\ Value=-1.09645e-07
-Laser\ Scan\ In..AxisUse\ Fixed\ Frame=1
-Laser\ Scan\ In..Flat\ ColorColorR=1
-Laser\ Scan\ In..Flat\ ColorColorG=1
-Laser\ Scan\ In..Flat\ ColorColorB=1
-Laser\ Scan\ In..IntensityAutocompute\ Intensity\ Bounds=1
-Laser\ Scan\ In..IntensityMax\ ColorR=1
-Laser\ Scan\ In..IntensityMax\ ColorG=1
-Laser\ Scan\ In..IntensityMax\ ColorB=1
-Laser\ Scan\ In..IntensityMax\ Intensity=4096
-Laser\ Scan\ In..IntensityMin\ ColorR=0
-Laser\ Scan\ In..IntensityMin\ ColorG=0
-Laser\ Scan\ In..IntensityMin\ ColorB=0
-Laser\ Scan\ In..IntensityMin\ Intensity=0
-Laser\ Scan.Alpha=1
-Laser\ Scan.Billboard\ Size=0.01
-Laser\ Scan.Color\ Transformer=Flat Color
-Laser\ Scan.Decay\ Time=0
-Laser\ Scan.Enabled=1
-Laser\ Scan.Position\ Transformer=XYZ
-Laser\ Scan.Selectable=1
-Laser\ Scan.Style=0
-Laser\ Scan.Topic=scan3
-Laser\ Scan..AxisAutocompute\ Value\ Bounds=1
-Laser\ Scan..AxisAxis=2
-Laser\ Scan..AxisMax\ Value=10
-Laser\ Scan..AxisMin\ Value=-10
-Laser\ Scan..AxisUse\ Fixed\ Frame=1
-Laser\ Scan..Flat\ ColorColorR=0
-Laser\ Scan..Flat\ ColorColorG=0
-Laser\ Scan..Flat\ ColorColorB=1
-Laser\ Scan..IntensityAutocompute\ Intensity\ Bounds=1
-Laser\ Scan..IntensityMax\ ColorR=1
-Laser\ Scan..IntensityMax\ ColorG=1
-Laser\ Scan..IntensityMax\ ColorB=1
-Laser\ Scan..IntensityMax\ Intensity=4096
-Laser\ Scan..IntensityMin\ ColorR=0
-Laser\ Scan..IntensityMin\ ColorG=0
-Laser\ Scan..IntensityMin\ ColorB=0
-Laser\ Scan..IntensityMin\ Intensity=0
-Tool\ 2D\ Nav\ GoalTopic=goal
-Tool\ 2D\ Pose\ EstimateTopic=initialpose
-Camera\ Type=rviz::OrbitViewController
-Camera\ Config=0.621 1.57915 6.81013 0.281448 0.0839437 -0.509401
-Property\ Grid\ State=selection=Laser Scan In.Enabled;expanded=.Global Options;scrollpos=0,0;splitterpos=132,266;ispageselected=1
-[Display0]
-Name=Grid
-Package=rviz
-ClassName=rviz::GridDisplay
-[Display1]
-Name=Laser Scan In
-Package=rviz
-ClassName=rviz::LaserScanDisplay
-[Display2]
-Name=Laser Scan 1
-Package=rviz
-ClassName=rviz::LaserScanDisplay
-[Display3]
-Name=Laser Scan 2
-Package=rviz
-ClassName=rviz::LaserScanDisplay
-[Display4]
-Name=Laser Scan
-Package=rviz
-ClassName=rviz::LaserScanDisplay
diff --git a/laser_scan_splitter/include/laser_scan_splitter/laser_scan_splitter.h b/laser_scan_splitter/include/laser_scan_splitter/laser_scan_splitter.h
deleted file mode 100644
index a00d2ab..0000000
--- a/laser_scan_splitter/include/laser_scan_splitter/laser_scan_splitter.h
+++ /dev/null
@@ -1,73 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef LASER_SCAN_SPLITTER_LASER_SCAN_SPLITTER_H
-#define LASER_SCAN_SPLITTER_LASER_SCAN_SPLITTER_H
-
-#include
-#include
-
-namespace scan_tools {
-
-const std::string scan_topic_ = "scan";
-
-class LaserScanSplitter
-{
- private:
-
- // **** ROS-related
- ros::NodeHandle nh_;
- ros::NodeHandle nh_private_;
- ros::Subscriber scan_subscriber_;
- std::vector scan_publishers_;
-
- // **** paramaters
-
- std::vector published_scan_topics_;
- std::vector published_laser_frames_;
- std::vector sizes_;
-
- // **** state variables
-
- unsigned int size_sum_;
-
- // **** member functions
-
- void scanCallback (const sensor_msgs::LaserScanConstPtr& scan_msg);
- void tokenize (const std::string& str, std::vector& tokens);
-
- public:
-
- LaserScanSplitter (ros::NodeHandle nh, ros::NodeHandle nh_private);
- virtual ~ LaserScanSplitter ();
-};
-
-} //namespace scan_tools
-
-#endif // LASER_SCAN_SPLITTER_LASER_SCAN_SPLITTER_H
diff --git a/laser_scan_splitter/include/laser_scan_splitter/laser_scan_splitter_nodelet.h b/laser_scan_splitter/include/laser_scan_splitter/laser_scan_splitter_nodelet.h
deleted file mode 100644
index 39fa1df..0000000
--- a/laser_scan_splitter/include/laser_scan_splitter/laser_scan_splitter_nodelet.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef LASER_SCAN_SPLITTER_LASER_SCAN_SPLITTER_NODELET_H
-#define LASER_SCAN_SPLITTER_LASER_SCAN_SPLITTER_NODELET_H
-
-#include
-#include
-
-#include "laser_scan_splitter/laser_scan_splitter.h"
-
-namespace scan_tools {
-
-class LaserScanSplitterNodelet : public nodelet::Nodelet
-{
- public:
- virtual void onInit();
-
- private:
- LaserScanSplitter * laser_scan_splitter_; // FIXME: change to smart pointer
-};
-
-} //namespace scan_tools
-
-#endif // LASER_SCAN_SPLITTER_LASER_SCAN_SPLITTER_NODELET_H
diff --git a/laser_scan_splitter/laser_scan_splitter_nodelet.xml b/laser_scan_splitter/laser_scan_splitter_nodelet.xml
deleted file mode 100644
index 33c60a9..0000000
--- a/laser_scan_splitter/laser_scan_splitter_nodelet.xml
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
-
- Laser scan splitter nodelet publisher.
-
-
-
diff --git a/laser_scan_splitter/package.xml b/laser_scan_splitter/package.xml
deleted file mode 100644
index 56a5a8a..0000000
--- a/laser_scan_splitter/package.xml
+++ /dev/null
@@ -1,30 +0,0 @@
-
- laser_scan_splitter
- 0.3.3
-
- The laser_scan_splitter takes in a LaserScan message and splits it into a number of other LaserScan messages. Each of the resulting laser scans can be assigned an arbitrary coordinate frame, and is published on a separate topic.
-
- Ivan Dryanovski
- Carlos
-
- http://wiki.ros.org/laser_scan_splitter
- Ivan Dryanovski
- William Morris
-
- BSD
-
- catkin
-
- roscpp
- nodelet
- sensor_msgs
-
- roscpp
- nodelet
- sensor_msgs
-
-
-
-
-
-
diff --git a/laser_scan_splitter/src/laser_scan_splitter.cpp b/laser_scan_splitter/src/laser_scan_splitter.cpp
deleted file mode 100644
index 9701ca7..0000000
--- a/laser_scan_splitter/src/laser_scan_splitter.cpp
+++ /dev/null
@@ -1,148 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_scan_splitter/laser_scan_splitter.h"
-
-namespace scan_tools {
-
-LaserScanSplitter::LaserScanSplitter(ros::NodeHandle nh, ros::NodeHandle nh_private):
- nh_(nh),
- nh_private_(nh_private)
-{
- ROS_INFO ("Starting LaserScanSplitter");
-
- // **** get paramters
-
- std::string topics_string;
- std::string frames_string;
- std::string sizes_string;
-
- if (!nh_private_.getParam ("topics", topics_string))
- topics_string = "scan1 scan2";
- if (!nh_private_.getParam ("frames", frames_string))
- frames_string = "laser laser";
- if (!nh_private_.getParam ("sizes", sizes_string))
- sizes_string = "256 256";
-
- // **** tokenize inputs
- tokenize (topics_string, published_scan_topics_);
- tokenize (frames_string, published_laser_frames_);
-
- std::vector sizes_tokens;
- tokenize (sizes_string, sizes_tokens);
-
- size_sum_ = 0;
- for (unsigned int i = 0; i < sizes_tokens.size (); i++)
- {
- sizes_.push_back (atoi (sizes_tokens[i].c_str ()));
- size_sum_ += sizes_[i];
-
- ROS_ASSERT_MSG ((sizes_[i] > 0), "LaserScanSplitter: Scan size cannot be zero. Quitting.");
- }
-
- // **** check that topic, frames, and sizes vectors have same sizes
-
- ROS_ASSERT_MSG ((published_scan_topics_.size () == published_laser_frames_.size ()) &&
- (sizes_.size () == published_laser_frames_.size ()),
- "LaserScanSplitter: Invalid parameters. Quitting.");
-
- // **** subscribe to laser scan messages
- scan_subscriber_ = nh_.subscribe (scan_topic_, 10, &LaserScanSplitter::scanCallback, this);
-
- // **** advertise topics
- for (unsigned int i = 0; i < published_scan_topics_.size (); i++)
- {
- scan_publishers_.push_back (ros::Publisher ());
- scan_publishers_[i] =
- nh_.advertise(published_scan_topics_[i], 10);
- }
-}
-
-LaserScanSplitter::~LaserScanSplitter ()
-{
- ROS_INFO ("Destroying LaserScanSplitter");
-}
-
-void LaserScanSplitter::scanCallback (const sensor_msgs::LaserScanConstPtr & scan_msg)
-{
- // **** check for scan size
- if (size_sum_ != scan_msg->ranges.size ())
- {
- ROS_WARN ("LaserScanSplitter: Received a laser scan with size (%d) \
- incompatible to input parameters. Skipping scan.", (int)scan_msg->ranges.size());
- return;
- }
-
- // **** copy information over
- int r = 0;
-
- for (unsigned int i = 0; i < published_scan_topics_.size (); i++)
- {
- sensor_msgs::LaserScan::Ptr scan_segment;
- scan_segment = boost::make_shared();
-
- scan_segment->header = scan_msg->header;
- scan_segment->range_min = scan_msg->range_min;
- scan_segment->range_max = scan_msg->range_max;
- scan_segment->angle_increment = scan_msg->angle_increment;
- scan_segment->time_increment = scan_msg->time_increment;
- scan_segment->scan_time = scan_msg->scan_time;
- scan_segment->header.frame_id = published_laser_frames_[i];
-
- scan_segment->angle_min =
- scan_msg->angle_min + (scan_msg->angle_increment * r);
- scan_segment->angle_max =
- scan_msg->angle_min + (scan_msg->angle_increment * (r + sizes_[i] - 1));
-
- // TODO - also copy intensity values
-
- scan_segment->ranges.resize(sizes_[i]);
- memcpy(&scan_segment->ranges[0], &scan_msg->ranges[r], sizes_[i]*sizeof(int));
- r+=sizes_[i];
-
- scan_publishers_[i].publish (scan_segment);
- }
-}
-
-void LaserScanSplitter::tokenize (const std::string & str, std::vector < std::string > &tokens)
-{
- std::string::size_type last_pos = str.find_first_not_of (" ", 0);
- std::string::size_type pos = str.find_first_of (" ", last_pos);
-
- while (std::string::npos != pos || std::string::npos != last_pos)
- {
- std::string string_token = str.substr (last_pos, pos - last_pos);
- tokens.push_back (string_token);
- last_pos = str.find_first_not_of (" ", pos);
- pos = str.find_first_of (" ", last_pos);
- }
-}
-
-} //namespace scan_tools
-
diff --git a/laser_scan_splitter/src/laser_scan_splitter_nodelet.cpp b/laser_scan_splitter/src/laser_scan_splitter_nodelet.cpp
deleted file mode 100644
index b5c36ae..0000000
--- a/laser_scan_splitter/src/laser_scan_splitter_nodelet.cpp
+++ /dev/null
@@ -1,45 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "laser_scan_splitter/laser_scan_splitter_nodelet.h"
-
-typedef scan_tools::LaserScanSplitterNodelet LaserScanSplitterNodelet;
-
-PLUGINLIB_EXPORT_CLASS(LaserScanSplitterNodelet, nodelet::Nodelet)
-
-void LaserScanSplitterNodelet::onInit ()
-{
- NODELET_INFO("Initializing LaserScanSplitter Nodelet");
-
- // TODO: Do we want the single threaded or multithreaded NH?
- ros::NodeHandle nh = getMTNodeHandle();
- ros::NodeHandle nh_private = getMTPrivateNodeHandle();
-
- laser_scan_splitter_ = new LaserScanSplitter(nh, nh_private);
-}
diff --git a/ncd_parser/CHANGELOG.rst b/ncd_parser/CHANGELOG.rst
deleted file mode 100644
index fe68604..0000000
--- a/ncd_parser/CHANGELOG.rst
+++ /dev/null
@@ -1,22 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package ncd_parser
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-
-0.3.3 (2021-02-15)
-------------------
-
-0.3.2 (2016-03-19)
-------------------
-
-0.3.1 (2015-12-18)
-------------------
-
-0.3.0 (2015-11-10)
-------------------
-
-0.2.1 (2015-10-14)
-------------------
-* [doc] README files to contain catkin instructions
-* [sys] Catkinization: ncd_parser
-* [sys] Small tweaks to CMakeLists.txt and package.xml files
-* Contributors: Ivan Dryanovski, Miguel Sarabia
diff --git a/ncd_parser/CMakeLists.txt b/ncd_parser/CMakeLists.txt
deleted file mode 100644
index 361f8b6..0000000
--- a/ncd_parser/CMakeLists.txt
+++ /dev/null
@@ -1,30 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(ncd_parser)
-
-# List C++ dependencies on ros packages
-set( ROS_CXX_DEPENDENCIES
- roscpp
- sensor_msgs
- tf )
-
-# Find catkin and all required ROS components
-find_package(catkin REQUIRED COMPONENTS ${ROS_CXX_DEPENDENCIES})
-
-# Set include directories
-include_directories(include ${catkin_INCLUDE_DIRS})
-
-# Declare info that other packages need to import library generated here
-catkin_package()
-
-#Create node
-add_executable( ${PROJECT_NAME} src/ncd_parser.cpp)
-target_link_libraries( ${PROJECT_NAME} ${catkin_LIBRARIES})
-add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS})
-
-#Install node
-install(TARGETS ${PROJECT_NAME}
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} )
-
-#Install demo directory
-install(DIRECTORY demo
- DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} )
diff --git a/ncd_parser/README.md b/ncd_parser/README.md
deleted file mode 100644
index a845bdc..0000000
--- a/ncd_parser/README.md
+++ /dev/null
@@ -1,24 +0,0 @@
-DESCRIPTION:
------------------------------------
-
-The ncd_parser package reads in .alog data files from the New College Dataset and
-broadcasts scan and odometry messages to ROS.
-
-INSTRUCTIONS:
------------------------------------
-
-To compile, see scan_tools's `README.md`
-
-To test, run:
-
- roslaunch ncd_parser demo.launch
-
-ACKNOWLEDGEMENTS:
------------------------------------
-
-QuadTree_Alog.alog used with the permission of Dr. Paul Newman, Oxford University.
-
-M. Smith, I. Baldwin, W. Churchill, R. Paul, and P. Newman, The new
-college vision and laser data set, International Journal for Robotics
-Research (IJRR), vol. 28, no. 5, pp. 595599, May 2009.
-
diff --git a/ncd_parser/demo/QuadTree_Alog.alog b/ncd_parser/demo/QuadTree_Alog.alog
deleted file mode 100644
index 6da1f99..0000000
--- a/ncd_parser/demo/QuadTree_Alog.alog
+++ /dev/null
@@ -1,1283 +0,0 @@
-%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
-%% LOG FILE: /home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/MOOSLog_3_11_2008_____13_43_32.alog
-%% FILE OPENED ON Mon Nov 3 13:43:32 2008
-%% LOGSTART 1225719811.65
-%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
--3.466 MISSION_FILE Antler{Monarch} ANTLERFILTER:
-#begbroke - the door to the lab...
-LatOrigin = 51.818496
-LongOrigin = -1.308591
-ServerHost = lisa1
-ServerPort = 9000
-Simulator = false
-GlobalLogPath = /home/mrg/MOOSData/LisaNewCollege
-MaximumVehicleSpeed = 1.7
-MaximumVehicleTurnRate = 0.5
-define:XTERM_BEIGE=#BBB6A7
-define:XTERM_LIGHT_BLUE=#0B4583
-define:SharedBin=/home/mrg/shared/bin
-ProcessConfig = ANTLER
-{
-EnableDistributed = true
-MSBetweenLaunches = 50
-ExecutablePath=/home/mrg/shared/bin
-Run = MOOSDB @ NewConsole = true
-Run = iPlatform @ NewConsole = true,XConfig=XPlatform
-Run = iRelayBox @ NewConsole = true
-Run = iRemote @ NewConsole = true
-Run = pLogger @ NewConsole = true
-Run = pNav @ NewConsole = true
-Run = iJoystick @ NewConsole = true
-Run = uWatchdog @ NewConsole = true
-Run = iGPS @ AntlerID = lisa2,NewConsole = true
-Run = iLMSLisaMulti @ AntlerID = lisa3, NewConsole=true ~ LMS1
-Run = iLMSLisaMulti @ AntlerID = lisa3, NewConsole=true ~ LMS2
-Run = iCamera @ AntlerID = lisa3, NewConsole = true ~ iCameraLadybug
-Run = iCamera @ AntlerID = lisa4,NewConsole = true ~ iCameraBumbleBee
-Run = DataServer @ AntlerID = lisa4,NewConsole = true,InhibitMOOSParams = true,Xconfig = FDSXConfig
-Run = pLogStereo @ AntlerID = lisa4,NewConsole = true,XConfig=XLogStereo
-XHelm=-bg,#BBB6A7,-T,TheHelm,
-XPlatform=-bg,#0B4583,-T,iPlatform
-XLogStereo=-geometry,180x20+700+500,-bg,#cccccc,-T,pLogStereo
-FDSXConfig = -bg, #F0F000
-FDSParams = -v,5
-}
-ProcessConfig = iPlatform
-{
-AppTick = 30
-CommsTick = 30
-VehicleName = LISA
-UseXSens = false
-XSensPort = /dev/ttyS1
-XSensFreq = 20
-OdometryName = ODOMETRY_POSE
-}
-ProcessConfig = iRelayBox
-{
-AppTick = 2
-CommsTick = 2
-Port = /dev/ttyS1
-BaudRate = 9600
-Streaming = false
-CIRCUIT : Port = 1, Name = LMS1, InitialState = LAST
-CIRCUIT : Port = 2, Name = LMS2, InitialState = LAST
-CIRCUIT : Port = 3, Name = LADYBUG, InitialState = LAST
-CIRCUIT : Port = 4, Name = PANTILT, InitialState = LAST
-CIRCUIT : Port = 5, Name = P5, InitialState = LAST
-CIRCUIT : Port = 6, Name = P6, InitialState = LAST
-CIRCUIT : Port = 7, Name = P7, InitialState = LAST
-CIRCUIT : Port = 8, Name = P8, InitialState = LAST
-CIRCUIT : Port = 9, Name = P9, InitialState = LAST
-CIRCUIT : Port = 10, Name = P10, InitialState = LAST
-CIRCUIT : Port = 11, Name = P11, InitialState = LAST
-CIRCUIT : Port = 12, Name = P12, InitialState = LAST
-CIRCUIT : Port = 13, Name = P13, InitialState = LAST
-CIRCUIT : Port = 14, Name = P14, InitialState = LAST
-CIRCUIT : Port = 15, Name = P15, InitialState = LAST
-CIRCUIT : Port = 16, Name = P16, InitialState = LAST
-WatchdogTimeout = 20.0
-}
-ProcessConfig = uWatchdog
-{
-AppTick = 1
-CommsTick = 1
-StartupGracePeriod = 30
-WatchedVariables = GPS
-WatchedProcesses = pLogStereo,iCamera,LMS1,LMS2
-VariableTimeout = 5
-}
-ProcessConfig = iRemote
-{
-CommsTick = 30
-AppTick = 30
-CustomKey = 1: RELAYBOX_CMD @ "LMS1=TOGGLE"
-CustomKey = 2: RELAYBOX_CMD @ "LMS2=TOGGLE"
-CustomKey = 3: RELAYBOX_CMD @ "LADYBUG=TOGGLE"
-CustomKey = 4: RELAYBOX_CMD @ "PANTILT=TOGGLE"
-CustomKey = 5: PANTILT_RESET_COMMAND @ ""
-CustomKey = 0: RELAYBOX_CMD @ "LMS1=OFF,LMS2=OFF,LADYBUG=OFF,PANTILT=OFF,P5=OFF,P6=OFF,P7=OFF,P8=OFF,P9=OFF,P10=OFF,P11=OFF,P12=OFF,P13=OFF,P14=OFF,P15=OFF,P16=OFF"
-CustomSummary = RELAYBOX_STATUS
-}
-ProcessConfig = pLogger
-{
-AppTick = 40.0
-CommsTick = 40.0
-PATH = /home/mrg/MOOSData/LisaNewCollege
-SyncLog = true @ 0.2
-AsyncLog = true
-FileTimeStamp = true
-WildCardLogging = true
-}
-ProcessConfig = pNav
-{
-Pose = ODOMETRY @ 2.0
-UseLSQ = false
-UseEKF = false
-USETOPDOWN = false
-}
-ProcessConfig = iGPS
-{
-AppTick = 8
-CommsTick = 4
-Port = /dev/ttyR1
-Type = SERES
-verbose = true
-BaudRate = 9600
-Streaming = true
-PublishRaw = true
-CombineMessages = true
-}
-ProcessConfig = iLogGPS_SeresBinary
-{
-AppTick = 8
-CommsTick = 4
-Port = /dev/ttyR1
-BaudRate = 9600
-Streaming = true
-RequestBinary = true
-}
-ProcessConfig = iCameraLadybug
-{
-AppTick = 0
-CommsTick = 10
-VerboseLevel = 1
-OutputColorMode = RGB_INTERLACED_8
-CameraDevice = DriverName=LadyBug,CamIdVect=[1x5]{0,1,2,3,4}
-CameraFeatures = BRIGHTNESS=AUTO,SHUTTER=AUTO,EXPOSURE=AUTO,GAIN=AUTO,GAMMA=MANUAL,GAMMAVal=0
-GrabSettings = Framerate=MAX
-WriteImagesToDisk = true
-FileIOSettings = NameStem=ladybug,Type=jpg,NameRule=TIME_STAMP
-FileIOCaptureSettings = Framerate = MAX
-UseBinaryCache = false
-BinaryCacheSettings = Host=localhost,PortID=9100
-UseDynamicLogPath = true
-UseDataServer = false
-Host=localhost,PortID=5555,SubscriptionName=Unibrain
-DataServerSettings = Host=telemachos,PortID=5555,SubscriptionName=Unibrain
-UsePanTilt = false
-OdometryName = NAV_POSE
-}
-ProcessConfig = LMS1
-{
-AppTick = 20
-CommsTick = 40
-Port = /dev/ttyUSB0
-500KBPS = true
-PublishAs = LMS_LASER_2D
-BaudRate = 500000
-Verbose = true
-Streaming = false
-Debug = true
-UseCSMExt = false
-LMSStreamingType = 80
-}
-ProcessConfig = LMS2
-{
-AppTick = 20
-CommsTick = 40
-Port = /dev/ttyUSB1
-500KBPS = true
-PublishAs = LMS_LASER_2D
-BaudRate = 500000
-Verbose = true
-Streaming = false
-Debug = true
-UseCSMExt = false
-LMSStreamingType = 80
-}
-ProcessConfig = iCameraBumbleBee
-{
-AppTick = 0
-CommsTick = 15
-VerboseLevel = 1
-CameraDevice = DriverName=BumbleBee
-OutputColorMode = BUMBLEBEE_512x384_MONO
-CameraFeatures = BRIGHTNESS=AUTO,SHUTTER=AUTO,EXPOSURE=AUTO,GAIN=AUTO,GAMMA=MANUAL,GAMMAVal=0
-GrabSettings=Framerate=MAX
-UseDataServer = true
-DataServerSettings = Host=lisa4,PortID=5555,SubscriptionName=BumbleBee
-DataServerCaptureSettings=Framerate=MAX
-OdometryName = NAV_POSE
-}
-ProcessConfig = pLogStereo
-{
-LoggingRoot = /home/mrg/MOOSData/LisaNewCollege
-NamingMode = Timed
-UseFDS = true
-FDSHost = lisa4
-BumbleBeeMode = BUMBLEBEE_512x384_MONO
-}
-
-61.855 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.2216,18.5450,-0.7993},Vel=[3x1]{-0.7904,-0.7686,-6.2821},Raw=[2x1]{19.9981,-0.7993},time=1225719873.50240921974182,Speed=1.10247948365994,Pitch=-0.00000000000000,Roll=0.03365030600758,PitchDot=0.03589365974142,RollDot=0.00132357870296
-61.855 ODOMETRY_POSE iPlatform Pose=[3x1]{4.2216,18.5450,-0.7990},Vel=[3x1]{-0.7904,-0.7686,0.0011},Raw=[2x1]{19.9981,-0.7993},time=1225719873.5024,Speed=1.1025,Pitch=-0.0241,Roll=0.0235,PitchDot=0.0359,RollDot=0.0013
-61.850 LMS_LASER_2D_LEFT LMS1 ID=4044,time=1225719873.501685,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=41,Range=[181]{1.054,1.051,1.059,1.068,1.067,1.086,1.085,1.091,1.102,1.122,1.135,1.143,1.161,1.160,1.187,1.198,1.217,1.226,1.238,1.253,1.274,1.279,1.291,1.315,1.330,1.345,1.363,1.381,1.396,1.423,1.449,1.458,1.484,1.511,1.527,1.553,1.573,1.603,1.623,1.653,1.691,1.721,1.750,1.784,1.811,1.848,1.885,1.937,1.968,2.021,2.069,2.117,2.160,2.208,2.257,2.310,2.365,2.413,2.501,2.547,2.608,2.676,2.752,2.841,2.960,2.981,2.979,3.029,3.175,3.282,3.379,3.494,3.615,3.654,3.648,3.648,3.642,3.710,3.858,3.987,4.063,4.098,4.101,4.109,4.201,4.128,4.148,4.294,4.267,4.225,4.223,4.223,4.225,4.256,4.423,4.532,4.539,4.551,4.557,4.559,4.566,4.567,4.568,4.574,4.584,4.582,4.593,4.604,4.605,4.610,4.621,4.629,4.637,4.648,4.659,4.668,4.672,4.585,4.700,4.718,4.730,4.684,4.593,4.755,3.891,3.777,3.845,3.869,3.770,3.782,3.636,3.664,3.442,3.391,3.354,3.378,4.970,3.268,3.410,5.038,5.050,5.074,5.092,2.702,2.794,2.724,2.757,2.834,2.844,2.979,2.991,2.543,2.325,2.296,2.302,2.356,2.488,2.349,2.309,2.359,2.511,3.474,2.855,2.756,3.604,5.751,5.718,5.782,5.921,5.969,6.010,6.060,6.114,6.161,6.216,6.257,6.313,6.367,6.421,6.473,6.531},Reflectance=[181]{40.000,43.000,44.000,43.000,45.000,41.000,46.000,46.000,46.000,47.000,45.000,48.000,48.000,43.000,41.000,46.000,50.000,48.000,49.000,48.000,49.000,51.000,53.000,52.000,51.000,54.000,54.000,54.000,53.000,54.000,54.000,54.000,54.000,54.000,54.000,58.000,59.000,57.000,58.000,60.000,61.000,62.000,59.000,58.000,59.000,59.000,59.000,55.000,63.000,58.000,57.000,60.000,60.000,63.000,59.000,59.000,62.000,58.000,54.000,50.000,58.000,61.000,63.000,63.000,59.000,70.000,69.000,59.000,52.000,49.000,54.000,48.000,53.000,60.000,62.000,61.000,63.000,67.000,65.000,68.000,69.000,66.000,67.000,67.000,66.000,68.000,65.000,63.000,53.000,41.000,39.000,36.000,35.000,45.000,63.000,77.000,76.000,77.000,76.000,77.000,76.000,76.000,77.000,76.000,76.000,76.000,76.000,74.000,75.000,73.000,74.000,74.000,71.000,75.000,75.000,75.000,76.000,74.000,76.000,77.000,75.000,78.000,74.000,75.000,84.000,72.000,91.000,103.000,94.000,97.000,96.000,104.000,84.000,85.000,72.000,38.000,75.000,39.000,111.000,74.000,75.000,75.000,77.000,64.000,106.000,76.000,78.000,79.000,77.000,67.000,34.000,15.000,59.000,73.000,67.000,56.000,68.000,73.000,69.000,71.000,87.000,44.000,57.000,60.000,34.000,68.000,61.000,67.000,63.000,65.000,67.000,69.000,69.000,69.000,70.000,68.000,69.000,66.000,67.000,67.000,65.000}
-61.879 DESIRED_THRUST iJoystick 85.5708487197
-61.879 DESIRED_RUDDER iJoystick 1.02847376934
-61.862 LMS_LASER_2D_RIGHT LMS2 ID=3917,time=1225719873.507227,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=6,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,27.473,17.169,14.143,12.123,10.511,9.465,8.595,7.748,7.139,6.607,6.098,5.655,5.310,5.007,4.723,4.429,4.194,3.999,3.767,3.593,3.460,3.302,3.133,3.001,2.890,2.780,2.671,2.561,2.469,2.365,2.302,2.239,2.184,2.114,2.054,1.986,1.915,1.884,1.842,1.809,1.760,1.708,1.680,1.652,1.614,1.577,1.551,1.492,1.475,1.446,1.405,1.385,1.364,1.333,1.312,1.301,1.288,1.271,1.255,1.253,1.249,1.257,1.271,1.271,1.240,1.220,1.226,1.233,1.231,1.223,1.209,1.198,1.178,1.151,1.143,1.131,1.119,1.097,1.083,1.107,1.110,1.093,1.085,1.070,1.066,1.059,1.051,1.040,1.021,0.979,0.975,0.974},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,79.000,119.000,88.000,77.000,60.000,58.000,58.000,60.000,65.000,67.000,67.000,68.000,69.000,70.000,72.000,72.000,73.000,74.000,76.000,78.000,79.000,80.000,81.000,80.000,81.000,81.000,81.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,78.000,79.000,80.000,80.000,81.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,74.000,77.000,76.000,77.000,75.000,75.000,73.000,76.000,77.000,79.000,79.000,79.000,79.000,75.000,64.000,57.000,53.000,67.000,74.000,72.000,68.000,60.000,56.000,53.000,48.000,44.000,43.000,41.000,31.000,30.000,27.000,27.000,31.000,36.000,41.000,43.000,45.000,43.000,43.000,41.000,41.000,32.000,25.000,26.000,28.000}
-61.863 LMS_LASER_2D_LEFT LMS1 ID=4045,time=1225719873.515017,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=42,Range=[181]{1.052,1.063,1.062,1.079,1.075,1.083,1.103,1.105,1.116,1.125,1.137,1.144,1.161,1.169,1.186,1.202,1.212,1.229,1.240,1.257,1.274,1.293,1.304,1.318,1.338,1.354,1.357,1.375,1.405,1.429,1.440,1.459,1.485,1.505,1.530,1.556,1.588,1.603,1.630,1.659,1.688,1.722,1.751,1.789,1.819,1.859,1.896,1.938,1.978,2.032,2.074,2.126,2.168,2.230,2.271,2.327,2.376,2.428,2.503,2.559,2.627,2.689,2.765,2.861,2.972,2.975,2.982,3.062,3.212,3.311,3.406,3.522,3.662,3.722,3.719,3.713,3.706,3.778,3.939,4.051,4.130,4.152,4.153,4.174,4.234,4.175,4.203,4.232,4.224,4.218,4.220,4.227,4.267,4.420,4.530,4.538,4.541,4.546,4.557,4.555,4.567,4.570,4.569,4.573,4.581,4.586,4.593,4.596,4.605,4.610,4.619,4.629,4.640,4.650,4.660,4.670,4.680,4.688,4.700,4.716,4.731,4.720,4.748,4.072,3.820,3.766,3.889,4.822,3.742,3.668,3.628,3.570,3.466,3.453,3.371,3.357,4.972,3.268,3.263,5.033,5.058,5.077,3.015,2.750,2.837,2.781,2.863,2.836,2.889,2.864,2.319,2.293,2.347,2.294,2.288,2.338,2.366,2.360,2.340,2.300,2.390,2.341,2.807,2.401,2.135,5.749,5.719,5.806,5.929,5.969,6.019,6.066,6.120,6.170,6.219,6.274,6.323,6.375,6.420,6.485,6.544},Reflectance=[181]{42.000,40.000,41.000,40.000,43.000,44.000,41.000,47.000,46.000,48.000,49.000,48.000,48.000,47.000,48.000,43.000,48.000,49.000,46.000,50.000,49.000,50.000,50.000,49.000,50.000,54.000,55.000,55.000,53.000,52.000,53.000,54.000,54.000,60.000,55.000,55.000,53.000,57.000,57.000,58.000,59.000,58.000,60.000,56.000,58.000,59.000,61.000,60.000,63.000,60.000,60.000,60.000,60.000,60.000,62.000,60.000,61.000,62.000,55.000,52.000,58.000,63.000,64.000,61.000,56.000,68.000,68.000,58.000,49.000,50.000,54.000,47.000,50.000,58.000,61.000,62.000,63.000,67.000,66.000,69.000,68.000,65.000,65.000,66.000,64.000,66.000,61.000,53.000,47.000,46.000,44.000,38.000,39.000,62.000,76.000,76.000,77.000,76.000,76.000,76.000,76.000,77.000,77.000,76.000,75.000,77.000,76.000,74.000,74.000,73.000,74.000,74.000,72.000,75.000,75.000,76.000,76.000,76.000,76.000,76.000,76.000,78.000,76.000,94.000,74.000,79.000,99.000,75.000,93.000,92.000,98.000,103.000,86.000,103.000,82.000,33.000,76.000,40.000,49.000,73.000,75.000,75.000,18.000,53.000,123.000,79.000,73.000,78.000,80.000,68.000,59.000,64.000,72.000,75.000,68.000,56.000,62.000,74.000,70.000,72.000,80.000,11.000,79.000,75.000,26.000,64.000,62.000,66.000,63.000,65.000,67.000,70.000,68.000,69.000,70.000,68.000,69.000,66.000,66.000,68.000,67.000}
-61.873 LMS_LASER_2D_RIGHT LMS2 ID=3918,time=1225719873.520565,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=7,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.746,13.796,11.783,10.273,9.344,8.489,7.621,7.042,6.514,6.026,5.612,5.283,4.981,4.655,4.366,4.169,3.955,3.743,3.566,3.434,3.266,3.107,2.983,2.857,2.769,2.661,2.552,2.452,2.355,2.283,2.230,2.167,2.095,2.036,1.969,1.919,1.875,1.833,1.798,1.760,1.719,1.681,1.631,1.595,1.559,1.530,1.484,1.441,1.421,1.396,1.385,1.343,1.333,1.315,1.290,1.280,1.263,1.262,1.254,1.247,1.251,1.263,1.284,1.274,1.241,1.226,1.225,1.229,1.222,1.209,1.195,1.176,1.151,1.145,1.137,1.115,1.094,1.088,1.072,1.099,1.088,1.081,1.079,1.063,1.061,1.048,1.044,1.034,1.015,1.017,0.999},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,91.000,117.000,88.000,75.000,58.000,58.000,57.000,61.000,66.000,68.000,67.000,68.000,69.000,72.000,72.000,73.000,73.000,75.000,76.000,78.000,79.000,80.000,80.000,81.000,80.000,80.000,81.000,81.000,81.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,78.000,78.000,78.000,77.000,77.000,74.000,71.000,73.000,76.000,74.000,72.000,74.000,77.000,79.000,79.000,79.000,79.000,77.000,69.000,58.000,51.000,51.000,68.000,76.000,70.000,62.000,55.000,53.000,51.000,47.000,43.000,44.000,37.000,29.000,27.000,27.000,27.000,34.000,37.000,40.000,45.000,45.000,44.000,41.000,42.000,39.000,34.000,36.000,33.000}
-61.886 LMS_LASER_2D_RIGHT LMS2 ID=3919,time=1225719873.533902,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=8,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.429,13.504,11.507,10.134,9.244,8.382,7.537,6.917,6.460,5.982,5.553,5.202,4.917,4.622,4.358,4.134,3.921,3.703,3.537,3.408,3.256,3.106,2.975,2.848,2.749,2.653,2.542,2.460,2.355,2.283,2.211,2.149,2.079,2.012,1.961,1.892,1.858,1.824,1.788,1.752,1.717,1.680,1.633,1.594,1.557,1.533,1.483,1.460,1.433,1.406,1.369,1.352,1.331,1.312,1.298,1.278,1.271,1.257,1.246,1.250,1.243,1.261,1.268,1.274,1.256,1.243,1.233,1.231,1.222,1.217,1.199,1.164,1.144,1.138,1.143,1.127,1.116,1.092,1.081,1.098,1.094,1.080,1.075,1.061,1.056,1.047,1.032,1.022,1.000,1.002,0.991},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,102.000,116.000,88.000,72.000,57.000,58.000,56.000,63.000,68.000,68.000,68.000,69.000,69.000,71.000,73.000,73.000,74.000,75.000,75.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,77.000,76.000,74.000,75.000,74.000,74.000,74.000,74.000,70.000,69.000,77.000,78.000,79.000,80.000,79.000,78.000,72.000,61.000,56.000,51.000,63.000,71.000,68.000,65.000,59.000,49.000,48.000,45.000,43.000,45.000,43.000,31.000,30.000,28.000,29.000,35.000,36.000,40.000,43.000,44.000,42.000,40.000,38.000,32.000,30.000,32.000,32.000}
-61.887 LMS_LASER_2D_LEFT LMS1 ID=4046,time=1225719873.528360,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=43,Range=[181]{1.063,1.064,1.060,1.079,1.077,1.075,1.096,1.108,1.118,1.128,1.135,1.149,1.161,1.179,1.188,1.201,1.215,1.235,1.241,1.257,1.271,1.285,1.304,1.318,1.344,1.353,1.363,1.392,1.411,1.423,1.441,1.468,1.477,1.506,1.528,1.564,1.586,1.613,1.637,1.669,1.700,1.729,1.763,1.792,1.824,1.861,1.904,1.941,1.987,2.036,2.087,2.134,2.177,2.227,2.286,2.340,2.393,2.443,2.504,2.565,2.648,2.707,2.781,2.875,2.975,2.973,2.976,3.092,3.238,3.326,3.439,3.564,3.681,3.801,3.789,3.774,3.782,3.837,4.007,4.117,4.186,4.217,4.220,4.237,4.231,4.214,4.218,4.217,4.221,4.224,4.217,4.259,4.412,4.529,4.539,4.540,4.541,4.545,4.555,4.555,4.566,4.570,4.569,4.571,4.581,4.588,4.590,4.594,4.602,4.612,4.619,4.631,4.635,4.648,4.661,4.668,4.671,4.688,4.701,4.716,4.731,4.737,4.749,3.987,3.908,3.840,4.806,3.611,3.719,3.612,3.594,3.436,3.443,3.472,3.408,3.367,4.980,3.247,3.244,3.264,5.056,5.070,3.012,3.014,3.188,2.926,2.873,2.801,2.576,2.374,2.256,2.249,2.281,2.277,2.281,2.301,2.420,2.391,2.301,2.234,2.265,2.424,2.435,2.182,2.163,5.737,5.720,5.812,5.929,5.978,6.022,6.072,6.127,6.177,6.224,6.271,6.331,6.376,6.427,6.493,6.550},Reflectance=[181]{39.000,39.000,42.000,40.000,42.000,45.000,46.000,51.000,43.000,49.000,45.000,50.000,47.000,47.000,49.000,44.000,46.000,48.000,50.000,50.000,52.000,50.000,50.000,47.000,53.000,53.000,54.000,51.000,52.000,54.000,54.000,54.000,55.000,56.000,54.000,55.000,56.000,58.000,56.000,59.000,56.000,58.000,61.000,58.000,56.000,61.000,61.000,62.000,64.000,62.000,58.000,60.000,60.000,63.000,61.000,57.000,62.000,61.000,61.000,55.000,55.000,63.000,64.000,59.000,58.000,65.000,63.000,56.000,49.000,49.000,52.000,47.000,47.000,58.000,61.000,63.000,63.000,66.000,66.000,67.000,65.000,63.000,64.000,64.000,62.000,61.000,55.000,54.000,52.000,49.000,42.000,40.000,62.000,76.000,76.000,77.000,77.000,76.000,76.000,76.000,76.000,77.000,77.000,75.000,75.000,78.000,75.000,74.000,74.000,74.000,74.000,74.000,73.000,75.000,76.000,75.000,76.000,76.000,77.000,76.000,76.000,78.000,76.000,94.000,89.000,93.000,75.000,17.000,95.000,86.000,99.000,75.000,34.000,112.000,87.000,32.000,76.000,31.000,47.000,18.000,75.000,76.000,31.000,40.000,101.000,76.000,68.000,70.000,78.000,85.000,75.000,75.000,76.000,75.000,69.000,50.000,71.000,78.000,80.000,68.000,72.000,87.000,78.000,73.000,33.000,63.000,63.000,65.000,63.000,65.000,68.000,70.000,67.000,69.000,69.000,67.000,69.000,66.000,66.000,67.000,66.000}
-61.891 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.2532,18.5759,-0.7971},Vel=[3x1]{-0.7949,-0.7765,0.1282},Raw=[2x1]{20.0423,-0.7971},time=1225719873.53830814361572,Speed=1.11124091002015,Pitch=-0.00000000000000,Roll=0.04038036720910,PitchDot=0.01570347613687,RollDot=0.00085247441886
-61.891 ODOMETRY_POSE iPlatform Pose=[3x1]{4.2532,18.5759,-0.7967},Vel=[3x1]{-0.7949,-0.7765,0.1282},Raw=[2x1]{20.0423,-0.7971},time=1225719873.5383,Speed=1.1112,Pitch=-0.0289,Roll=0.0282,PitchDot=0.0157,RollDot=-0.0012
-61.898 LMS_LASER_2D_LEFT LMS1 ID=4047,time=1225719873.541700,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=44,Range=[181]{1.055,1.071,1.061,1.076,1.075,1.084,1.093,1.108,1.116,1.131,1.131,1.155,1.165,1.177,1.187,1.200,1.220,1.228,1.246,1.259,1.274,1.300,1.309,1.324,1.336,1.354,1.371,1.396,1.408,1.424,1.441,1.475,1.487,1.519,1.536,1.568,1.595,1.614,1.638,1.669,1.706,1.733,1.769,1.793,1.828,1.872,1.905,1.954,1.999,2.037,2.093,2.137,2.192,2.235,2.286,2.339,2.394,2.446,2.506,2.580,2.661,2.717,2.783,2.896,2.978,2.976,2.975,3.126,3.239,3.330,3.456,3.586,3.724,3.879,3.864,3.849,3.853,3.916,4.081,4.177,4.259,4.290,4.273,4.255,4.215,4.208,4.213,4.206,4.218,4.218,4.260,4.428,4.531,4.532,4.541,4.539,4.541,4.543,4.546,4.558,4.557,4.558,4.566,4.573,4.580,4.585,4.587,4.596,4.605,4.614,4.620,4.631,4.638,4.647,4.661,4.672,4.673,4.690,4.700,3.445,4.731,4.737,4.743,4.750,3.989,4.077,4.801,3.795,3.735,3.637,3.487,3.491,4.906,3.332,3.477,3.394,4.973,3.206,3.303,3.221,5.058,5.072,3.040,3.030,3.192,3.029,2.872,2.794,3.112,2.357,2.269,2.247,2.243,2.253,2.271,2.304,2.462,2.517,2.407,2.258,2.233,2.302,2.220,2.146,2.140,5.734,5.713,5.820,5.929,5.979,6.030,2.606,6.135,6.176,6.225,6.273,6.328,6.382,6.435,6.492,6.550},Reflectance=[181]{37.000,40.000,42.000,42.000,44.000,45.000,43.000,44.000,46.000,50.000,46.000,49.000,47.000,47.000,49.000,51.000,48.000,45.000,48.000,51.000,49.000,49.000,49.000,52.000,54.000,54.000,53.000,53.000,54.000,54.000,54.000,54.000,55.000,54.000,58.000,57.000,56.000,58.000,56.000,59.000,59.000,56.000,60.000,63.000,58.000,57.000,61.000,59.000,60.000,63.000,61.000,61.000,58.000,63.000,61.000,62.000,62.000,62.000,57.000,53.000,57.000,63.000,64.000,56.000,55.000,63.000,63.000,50.000,54.000,51.000,52.000,45.000,50.000,59.000,60.000,61.000,64.000,67.000,67.000,65.000,63.000,65.000,67.000,65.000,62.000,58.000,57.000,57.000,50.000,43.000,41.000,65.000,76.000,77.000,77.000,76.000,77.000,75.000,76.000,76.000,76.000,76.000,76.000,76.000,75.000,76.000,74.000,74.000,75.000,75.000,74.000,74.000,74.000,74.000,76.000,76.000,76.000,76.000,76.000,11.000,76.000,78.000,77.000,76.000,95.000,98.000,76.000,100.000,94.000,96.000,82.000,85.000,75.000,23.000,101.000,28.000,76.000,32.000,93.000,31.000,75.000,76.000,19.000,50.000,98.000,96.000,65.000,68.000,56.000,91.000,76.000,74.000,73.000,74.000,74.000,68.000,73.000,76.000,93.000,75.000,68.000,78.000,75.000,70.000,30.000,65.000,64.000,65.000,63.000,65.000,68.000,12.000,67.000,69.000,70.000,68.000,68.000,65.000,66.000,67.000,66.000}
-61.903 DESIRED_THRUST iJoystick 85.5708487197
-61.903 DESIRED_RUDDER iJoystick 1.02847376934
-61.897 LMS_LASER_2D_RIGHT LMS2 ID=3920,time=1225719873.547237,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=9,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,23.343,16.190,13.191,11.254,10.054,9.125,8.270,7.463,6.847,6.419,5.921,5.543,5.165,4.864,4.561,4.339,4.126,3.894,3.703,3.529,3.373,3.234,3.090,2.942,2.840,2.742,2.640,2.533,2.452,2.362,2.283,2.209,2.141,2.062,2.012,1.951,1.907,1.859,1.815,1.788,1.741,1.707,1.671,1.625,1.586,1.557,1.536,1.500,1.440,1.412,1.387,1.368,1.349,1.332,1.315,1.304,1.280,1.271,1.254,1.252,1.242,1.235,1.249,1.256,1.272,1.256,1.246,1.236,1.224,1.228,1.227,1.202,1.168,1.149,1.140,1.145,1.132,1.118,1.115,1.107,1.091,1.083,1.070,1.070,1.063,1.056,1.049,1.031,1.022,0.988,0.994,0.970},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,2.000,110.000,117.000,89.000,67.000,58.000,58.000,55.000,66.000,68.000,68.000,67.000,69.000,71.000,72.000,72.000,73.000,74.000,75.000,77.000,79.000,80.000,80.000,81.000,81.000,81.000,79.000,81.000,81.000,80.000,80.000,80.000,81.000,80.000,81.000,79.000,79.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,77.000,73.000,72.000,73.000,70.000,73.000,72.000,69.000,72.000,76.000,78.000,79.000,79.000,79.000,78.000,78.000,72.000,66.000,64.000,54.000,64.000,62.000,58.000,56.000,54.000,46.000,43.000,43.000,42.000,46.000,44.000,34.000,32.000,46.000,49.000,38.000,33.000,39.000,44.000,45.000,46.000,41.000,38.000,34.000,29.000,30.000,28.000}
-61.909 LMS_LASER_2D_RIGHT LMS2 ID=3921,time=1225719873.560570,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=10,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.410,20.407,15.726,12.977,11.110,9.969,9.018,8.143,7.412,6.813,6.401,5.903,5.502,5.138,4.801,4.535,4.312,4.108,3.905,3.677,3.516,3.356,3.227,3.071,2.932,2.830,2.725,2.635,2.533,2.443,2.346,2.264,2.203,2.140,2.071,2.004,1.951,1.902,1.859,1.824,1.779,1.735,1.698,1.671,1.616,1.577,1.560,1.524,1.494,1.456,1.412,1.401,1.377,1.349,1.333,1.312,1.295,1.280,1.267,1.259,1.251,1.238,1.248,1.258,1.270,1.276,1.256,1.255,1.237,1.220,1.212,1.212,1.195,1.164,1.149,1.139,1.143,1.147,1.125,1.110,1.099,1.103,1.083,1.074,1.075,1.064,1.051,1.050,1.029,0.999,0.999,1.018,0.976},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,9.000,12.000,121.000,115.000,85.000,65.000,60.000,59.000,55.000,67.000,67.000,67.000,68.000,70.000,72.000,72.000,72.000,74.000,75.000,75.000,78.000,79.000,81.000,80.000,80.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,81.000,80.000,80.000,81.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,78.000,75.000,74.000,72.000,71.000,75.000,70.000,70.000,72.000,76.000,76.000,76.000,78.000,78.000,78.000,74.000,64.000,55.000,53.000,52.000,63.000,62.000,58.000,62.000,63.000,54.000,51.000,45.000,46.000,45.000,43.000,45.000,50.000,47.000,49.000,42.000,36.000,38.000,43.000,40.000,41.000,43.000,40.000,28.000,31.000,37.000,28.000}
-61.910 LMS_LASER_2D_LEFT LMS1 ID=4048,time=1225719873.555039,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=45,Range=[181]{1.060,1.063,1.057,1.063,1.074,1.091,1.104,1.109,1.113,1.125,1.143,1.152,1.167,1.175,1.182,1.207,1.214,1.232,1.254,1.252,1.280,1.291,1.311,1.327,1.348,1.361,1.371,1.388,1.406,1.423,1.450,1.484,1.496,1.527,1.549,1.566,1.591,1.617,1.646,1.677,1.701,1.735,1.775,1.802,1.830,1.883,1.913,1.962,2.004,2.055,2.090,2.143,2.188,2.236,2.298,2.343,2.401,2.455,2.519,2.599,2.668,2.732,2.796,2.912,2.978,2.967,2.982,3.148,3.247,3.359,3.466,3.623,3.731,3.880,3.933,3.927,3.922,3.978,4.132,4.267,4.345,4.346,4.295,4.245,4.199,4.199,4.201,4.206,4.215,4.253,4.430,4.533,4.532,4.533,4.539,4.540,4.539,4.544,4.547,4.547,4.548,4.561,4.567,4.573,4.573,4.576,4.587,4.587,4.605,4.616,4.616,4.631,4.642,4.646,4.659,4.663,4.675,3.440,3.569,3.580,4.737,4.737,4.744,3.861,3.962,4.785,3.701,3.717,3.852,3.640,3.555,3.630,4.903,3.431,3.511,3.382,4.971,3.195,3.290,3.249,5.061,5.071,5.101,3.204,3.124,3.038,2.872,2.899,3.059,2.411,2.319,2.275,2.259,2.277,2.319,2.375,2.439,2.507,2.462,2.364,2.264,2.252,2.153,2.140,2.158,5.732,5.716,5.826,5.938,5.980,6.031,2.629,6.134,6.177,6.229,6.285,6.326,6.385,6.436,6.501,6.555},Reflectance=[181]{38.000,40.000,46.000,46.000,44.000,46.000,49.000,48.000,46.000,44.000,45.000,43.000,46.000,46.000,46.000,50.000,49.000,47.000,43.000,46.000,52.000,49.000,50.000,49.000,50.000,53.000,53.000,53.000,53.000,54.000,54.000,54.000,55.000,54.000,56.000,56.000,55.000,60.000,56.000,58.000,61.000,61.000,58.000,58.000,59.000,58.000,61.000,59.000,58.000,59.000,59.000,60.000,61.000,63.000,63.000,64.000,61.000,62.000,55.000,40.000,56.000,65.000,65.000,56.000,55.000,63.000,61.000,52.000,54.000,48.000,44.000,53.000,58.000,59.000,64.000,61.000,64.000,68.000,66.000,62.000,67.000,70.000,71.000,60.000,58.000,58.000,59.000,57.000,40.000,43.000,65.000,77.000,77.000,77.000,76.000,77.000,76.000,75.000,76.000,76.000,76.000,77.000,76.000,76.000,76.000,76.000,75.000,74.000,75.000,75.000,75.000,74.000,75.000,74.000,75.000,76.000,77.000,16.000,101.000,103.000,77.000,77.000,77.000,9.000,95.000,76.000,18.000,83.000,104.000,99.000,90.000,108.000,76.000,21.000,99.000,27.000,76.000,38.000,91.000,50.000,76.000,76.000,75.000,31.000,54.000,104.000,73.000,104.000,75.000,85.000,80.000,78.000,75.000,75.000,77.000,73.000,71.000,86.000,75.000,70.000,72.000,71.000,72.000,71.000,19.000,64.000,64.000,64.000,63.000,65.000,68.000,11.000,67.000,69.000,68.000,68.000,67.000,66.000,66.000,67.000,65.000}
-61.922 LMS_LASER_2D_LEFT LMS1 ID=4049,time=1225719873.568377,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=46,Range=[181]{1.052,1.050,1.068,1.072,1.074,1.093,1.093,1.105,1.122,1.135,1.135,1.152,1.164,1.184,1.186,1.195,1.222,1.229,1.247,1.264,1.285,1.292,1.317,1.330,1.347,1.364,1.381,1.395,1.421,1.441,1.450,1.483,1.501,1.523,1.542,1.570,1.592,1.623,1.644,1.679,1.705,1.745,1.774,1.805,1.834,1.881,1.921,1.965,2.013,2.059,2.087,2.140,2.196,2.243,2.306,2.355,2.407,2.469,2.527,2.608,2.675,2.725,2.792,2.914,2.986,2.968,2.985,3.149,3.267,3.357,3.493,3.632,3.715,3.893,3.985,4.006,4.010,4.052,4.202,4.355,4.330,4.355,4.311,4.221,4.205,4.198,4.197,4.213,4.287,4.429,4.529,4.532,4.534,4.531,4.533,4.532,4.539,4.535,4.547,4.548,4.550,4.552,4.561,4.565,4.575,4.575,4.585,4.587,4.598,4.605,4.614,4.622,4.633,4.644,4.659,4.663,4.672,3.420,3.507,3.526,3.460,4.737,4.743,4.058,4.093,4.787,3.814,3.790,3.861,3.722,3.706,3.489,4.894,3.409,3.435,3.382,4.972,3.180,3.308,3.353,3.288,5.072,5.095,5.122,2.968,3.026,2.866,2.819,2.975,2.950,2.450,2.394,2.377,2.436,2.381,2.455,2.431,2.247,2.314,2.340,2.298,2.207,2.142,2.132,5.744,5.729,5.710,5.832,5.938,5.989,6.035,2.604,6.131,6.180,6.229,6.285,6.335,6.382,6.443,6.503,6.549},Reflectance=[181]{42.000,43.000,43.000,47.000,44.000,43.000,46.000,46.000,50.000,48.000,47.000,43.000,46.000,48.000,46.000,45.000,49.000,49.000,49.000,49.000,50.000,49.000,49.000,51.000,50.000,54.000,54.000,52.000,53.000,54.000,54.000,53.000,54.000,56.000,56.000,58.000,55.000,54.000,60.000,59.000,59.000,57.000,58.000,60.000,61.000,57.000,61.000,61.000,59.000,61.000,58.000,58.000,61.000,62.000,62.000,61.000,60.000,61.000,59.000,47.000,55.000,66.000,64.000,57.000,55.000,59.000,59.000,53.000,50.000,45.000,43.000,58.000,59.000,62.000,65.000,63.000,64.000,69.000,64.000,67.000,73.000,75.000,68.000,51.000,57.000,63.000,57.000,47.000,50.000,65.000,76.000,77.000,77.000,76.000,77.000,77.000,76.000,75.000,76.000,76.000,77.000,78.000,77.000,76.000,76.000,76.000,74.000,75.000,75.000,75.000,75.000,75.000,75.000,73.000,75.000,76.000,76.000,15.000,95.000,97.000,17.000,77.000,77.000,97.000,98.000,77.000,93.000,103.000,104.000,107.000,109.000,33.000,76.000,39.000,85.000,28.000,76.000,24.000,91.000,108.000,11.000,76.000,76.000,76.000,26.000,102.000,74.000,78.000,70.000,71.000,87.000,88.000,83.000,75.000,74.000,76.000,71.000,74.000,73.000,73.000,74.000,71.000,69.000,64.000,65.000,66.000,65.000,63.000,63.000,65.000,69.000,18.000,66.000,70.000,68.000,68.000,67.000,65.000,65.000,67.000,63.000}
-61.923 UWATCHDOG_STATUS uWatchdog AppErrorFlag=false,Uptime=61.2664,MOOSName=uWatchdog,Publishing=MOOS_DEBUG,UWATCHDOG_STATUS,Subscribing=GPS,ICAMERA_STATUS,LMS1_STATUS,LMS2_STATUS,PLOGSTEREO_STATUS,
-61.923 MOOS_DEBUG uWatchdog Variable GPS has not appeared in more than 5 seconds.
-
-61.923 MOOS_DEBUG uWatchdog Variable ICAMERA_STATUS has not appeared in more than 5 seconds.
-
-61.923 MOOS_DEBUG uWatchdog Watchdog reports an error!
-61.927 DESIRED_THRUST iJoystick 85.5708487197
-61.927 DESIRED_RUDDER iJoystick 1.02847376934
-61.927 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.2849,18.6069,-0.7962},Vel=[3x1]{-0.8015,-0.7844,3.4615},Raw=[2x1]{20.0867,-0.7962},time=1225719873.57443428039551,Speed=1.12146257410706,Pitch=-0.00000000000000,Roll=0.04262372094293,PitchDot=0.03589365974142,RollDot=0.00051597135878
-61.927 ODOMETRY_POSE iPlatform Pose=[3x1]{4.2849,18.6069,-0.7957},Vel=[3x1]{-0.8015,-0.7844,-2.8215},Raw=[2x1]{20.0867,-0.7962},time=1225719873.5744,Speed=1.1215,Pitch=-0.0305,Roll=0.0298,PitchDot=-0.0342,RollDot=0.0108
-61.951 DESIRED_THRUST iJoystick 85.5708487197
-61.951 DESIRED_RUDDER iJoystick 1.02847376934
-61.921 LMS_LASER_2D_RIGHT LMS2 ID=3922,time=1225719873.573903,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=11,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.458,-1.000,15.561,12.862,11.015,9.874,8.946,8.066,7.372,6.796,6.315,5.859,5.485,5.130,4.791,4.509,4.313,4.064,3.874,3.681,3.496,3.350,3.226,3.053,2.932,2.822,2.716,2.627,2.515,2.436,2.331,2.265,2.202,2.133,2.063,1.983,1.944,1.893,1.859,1.806,1.770,1.733,1.699,1.663,1.615,1.578,1.553,1.524,1.496,1.427,1.400,1.382,1.367,1.359,1.333,1.318,1.303,1.280,1.259,1.245,1.247,1.243,1.247,1.261,1.275,1.275,1.269,1.259,1.236,1.221,1.205,1.212,1.197,1.163,1.137,1.137,1.138,1.134,1.133,1.124,1.101,1.095,1.073,1.070,1.071,1.057,1.053,1.048,1.036,0.988,0.981,1.007,0.965},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,11.000,0.000,123.000,111.000,83.000,65.000,58.000,59.000,56.000,66.000,66.000,67.000,68.000,70.000,71.000,72.000,72.000,74.000,76.000,76.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,81.000,81.000,81.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,75.000,75.000,78.000,75.000,70.000,71.000,74.000,77.000,75.000,74.000,76.000,76.000,77.000,71.000,63.000,53.000,48.000,51.000,53.000,60.000,58.000,63.000,64.000,54.000,52.000,45.000,45.000,44.000,37.000,36.000,38.000,46.000,50.000,40.000,32.000,37.000,42.000,43.000,45.000,42.000,39.000,27.000,27.000,33.000,28.000}
-61.935 LMS_LASER_2D_LEFT LMS1 ID=4050,time=1225719873.581714,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=47,Range=[181]{1.047,1.059,1.060,1.076,1.075,1.093,1.102,1.102,1.114,1.126,1.141,1.152,1.164,1.177,1.190,1.201,1.220,1.238,1.246,1.263,1.281,1.296,1.309,1.330,1.343,1.348,1.381,1.388,1.423,1.442,1.457,1.476,1.499,1.527,1.547,1.573,1.599,1.616,1.650,1.679,1.713,1.740,1.772,1.812,1.843,1.896,1.929,1.962,2.014,2.062,2.092,2.143,2.203,2.245,2.312,2.360,2.409,2.480,2.531,2.617,2.677,2.743,2.794,2.913,2.973,2.959,2.991,3.139,3.278,3.389,3.513,3.641,3.748,3.940,4.028,4.101,4.096,4.125,4.263,4.323,4.259,4.223,4.210,4.206,4.194,4.192,4.214,4.313,4.456,4.491,4.529,4.522,4.532,4.534,4.534,4.534,4.532,4.539,4.539,4.548,4.550,4.550,4.557,4.563,4.564,4.573,4.578,4.590,4.589,4.608,4.614,4.633,4.634,4.648,4.651,4.664,4.675,4.683,3.526,3.471,3.641,4.737,4.742,4.100,4.770,3.819,3.837,3.946,3.859,4.847,3.499,3.671,3.467,3.517,3.421,3.410,4.973,3.382,3.357,3.346,3.286,5.073,5.094,2.824,2.744,2.834,2.783,2.713,2.769,2.903,2.680,2.605,2.568,2.445,2.376,2.299,2.071,2.052,2.112,2.125,2.173,2.220,2.156,2.172,5.745,5.723,5.713,5.832,5.938,5.979,6.031,2.583,2.581,6.177,6.229,6.275,6.334,6.381,6.434,6.501,6.549},Reflectance=[181]{46.000,45.000,45.000,43.000,44.000,42.000,42.000,46.000,46.000,45.000,51.000,45.000,46.000,45.000,50.000,44.000,48.000,41.000,45.000,48.000,48.000,51.000,53.000,51.000,53.000,55.000,54.000,53.000,54.000,54.000,53.000,54.000,57.000,54.000,55.000,55.000,55.000,59.000,58.000,59.000,58.000,59.000,61.000,59.000,56.000,56.000,60.000,59.000,59.000,58.000,61.000,60.000,60.000,63.000,61.000,59.000,61.000,61.000,61.000,54.000,56.000,66.000,65.000,56.000,56.000,63.000,57.000,53.000,51.000,50.000,45.000,58.000,54.000,59.000,67.000,61.000,63.000,67.000,64.000,71.000,66.000,57.000,50.000,53.000,61.000,64.000,53.000,53.000,73.000,76.000,76.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,76.000,77.000,77.000,76.000,75.000,76.000,76.000,75.000,75.000,75.000,75.000,75.000,75.000,75.000,74.000,75.000,76.000,77.000,77.000,96.000,80.000,110.000,78.000,76.000,96.000,77.000,4.000,98.000,104.000,103.000,77.000,29.000,110.000,29.000,105.000,83.000,29.000,76.000,42.000,87.000,93.000,33.000,77.000,76.000,20.000,59.000,79.000,72.000,73.000,76.000,69.000,119.000,92.000,86.000,73.000,70.000,71.000,76.000,68.000,78.000,74.000,76.000,72.000,73.000,53.000,63.000,67.000,66.000,63.000,63.000,65.000,68.000,26.000,18.000,69.000,68.000,68.000,67.000,65.000,65.000,67.000,63.000}
-61.963 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.3085,18.6299,-0.7966},Vel=[3x1]{-0.8049,-0.7872,3.4615},Raw=[2x1]{20.1197,-0.7966},time=1225719873.61052322387695,Speed=1.12584328728717,Pitch=0.00224335373384,Roll=0.04486707467677,PitchDot=0.03589365974142,RollDot=0.00038137013475
-61.963 ODOMETRY_POSE iPlatform Pose=[3x1]{4.3085,18.6299,-0.7960},Vel=[3x1]{-0.8049,-0.7872,-2.8215},Raw=[2x1]{20.1197,-0.7966},time=1225719873.6105,Speed=1.1258,Pitch=-0.0305,Roll=0.0330,PitchDot=-0.0342,RollDot=0.0109
-61.963 VEHICLE_GEOMETRY iPlatform Name=LISA, Sensor_0=LMS_LASER_2D, Pose3D_0=[4x1]{0.0000,0.3500,0.0000,0.0000},SHAPE_2D=[2x8]{0.3300,0.3300,0.2100,0.2100,-0.2100,-0.2100,-0.3300,-0.3300,-0.4100,0.4100,0.4100,0.5700,0.5700,0.4100,0.4100,-0.4100,}
-61.975 DESIRED_THRUST iJoystick 85.5708487197
-61.975 DESIRED_RUDDER iJoystick 1.02847376934
-61.846 PLOGSTEREO_STATUS pLogStereo Frame= 1183, ImageFrame= 001184, last grab 49ms ago, CaptureRate= 20.0, LogRate= 20.0, GrowthRate=-0.0, DroppedFrames= 0, WrittenFrames= 1182, 1 Frames Pending, DroppingEvery= 0 ,AppErrorFlag=false,Uptime=-1547.56,MOOSName=pLogStereo,Publishing=MOOS_DEBUG,PLOGSTEREO_STATUS,Subscribing=LOGGER_RESTART,PLOGSTEREO_CMD,
-61.934 LMS_LASER_2D_RIGHT LMS2 ID=3923,time=1225719873.587234,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=12,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.380,18.908,15.484,12.791,10.971,9.812,8.911,8.023,7.360,6.811,6.305,5.859,5.450,5.103,4.775,4.501,4.293,4.056,3.869,3.668,3.483,3.362,3.211,3.050,2.924,2.816,2.706,2.605,2.506,2.424,2.337,2.258,2.195,2.123,2.057,1.985,1.936,1.894,1.851,1.806,1.777,1.722,1.688,1.655,1.624,1.582,1.563,1.535,1.467,1.426,1.416,1.377,1.364,1.359,1.340,1.310,1.298,1.276,1.259,1.250,1.245,1.241,1.255,1.267,1.282,1.273,1.278,1.248,1.236,1.219,1.215,1.214,1.196,1.165,1.138,1.129,1.133,1.107,1.098,1.113,1.093,1.098,1.084,1.077,1.060,1.062,1.052,1.042,1.039,1.008,0.975,0.971,0.959},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,11.000,0.000,123.000,109.000,83.000,66.000,58.000,60.000,58.000,63.000,65.000,67.000,68.000,70.000,71.000,72.000,72.000,74.000,74.000,75.000,79.000,81.000,78.000,79.000,80.000,81.000,80.000,80.000,81.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,81.000,81.000,80.000,79.000,78.000,79.000,77.000,79.000,79.000,79.000,79.000,77.000,77.000,77.000,70.000,75.000,72.000,71.000,75.000,77.000,75.000,78.000,78.000,76.000,68.000,58.000,52.000,47.000,51.000,48.000,59.000,62.000,57.000,56.000,52.000,51.000,45.000,45.000,45.000,36.000,29.000,28.000,45.000,54.000,46.000,34.000,41.000,41.000,45.000,44.000,41.000,35.000,31.000,26.000,27.000,26.000}
-61.946 LMS_LASER_2D_LEFT LMS1 ID=4051,time=1225719873.595049,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=48,Range=[181]{1.062,1.052,1.062,1.067,1.077,1.081,1.112,1.099,1.120,1.135,1.148,1.144,1.170,1.179,1.198,1.202,1.225,1.230,1.251,1.264,1.283,1.288,1.311,1.327,1.345,1.364,1.382,1.391,1.424,1.441,1.460,1.494,1.504,1.520,1.547,1.570,1.599,1.616,1.651,1.676,1.708,1.741,1.773,1.808,1.843,1.887,1.928,1.965,2.016,2.060,2.090,2.155,2.204,2.259,2.312,2.357,2.410,2.478,2.532,2.603,2.704,2.740,2.819,2.922,2.969,2.958,2.991,3.150,3.274,3.381,3.518,3.652,3.783,3.956,4.094,4.201,4.189,4.186,4.215,4.198,4.209,4.199,4.191,4.192,4.195,4.211,4.340,4.456,4.486,4.492,4.537,4.527,4.527,4.526,4.526,4.533,4.533,4.540,4.543,4.541,4.543,4.551,4.551,4.558,4.570,4.568,4.583,4.591,4.597,4.600,4.608,4.615,4.635,4.641,4.654,4.665,4.667,4.682,3.572,3.463,3.581,4.730,4.736,4.743,4.771,4.780,4.055,3.805,3.655,4.842,4.863,3.471,3.601,3.503,3.496,3.428,4.969,3.460,3.392,3.353,3.209,3.080,3.040,2.751,2.742,2.835,2.722,2.617,2.620,2.534,2.501,2.509,2.532,2.520,2.346,2.142,2.041,2.032,2.042,2.057,2.082,2.143,2.128,2.228,2.197,5.732,5.707,5.810,5.930,5.983,6.029,2.589,2.626,6.177,6.228,6.275,6.326,6.372,6.433,6.494,5.132},Reflectance=[181]{38.000,46.000,47.000,44.000,43.000,46.000,42.000,46.000,47.000,48.000,50.000,45.000,47.000,48.000,49.000,46.000,47.000,46.000,50.000,44.000,49.000,51.000,54.000,53.000,53.000,54.000,54.000,54.000,54.000,53.000,54.000,54.000,54.000,54.000,54.000,57.000,55.000,59.000,58.000,57.000,59.000,59.000,62.000,61.000,56.000,55.000,59.000,60.000,60.000,61.000,63.000,57.000,59.000,60.000,60.000,61.000,61.000,60.000,61.000,55.000,55.000,65.000,64.000,56.000,58.000,65.000,57.000,47.000,49.000,50.000,47.000,47.000,49.000,63.000,65.000,58.000,62.000,60.000,61.000,56.000,54.000,57.000,58.000,58.000,60.000,55.000,56.000,73.000,76.000,75.000,75.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,76.000,77.000,77.000,77.000,76.000,77.000,76.000,75.000,75.000,75.000,75.000,75.000,75.000,75.000,75.000,76.000,76.000,77.000,76.000,102.000,80.000,103.000,77.000,76.000,76.000,77.000,77.000,100.000,88.000,17.000,77.000,76.000,32.000,105.000,99.000,101.000,31.000,75.000,89.000,89.000,98.000,25.000,36.000,34.000,56.000,78.000,77.000,75.000,71.000,72.000,62.000,71.000,74.000,75.000,74.000,74.000,76.000,74.000,69.000,69.000,71.000,71.000,74.000,75.000,71.000,33.000,69.000,66.000,64.000,62.000,66.000,67.000,19.000,22.000,69.000,67.000,68.000,67.000,65.000,65.000,64.000,31.000}
-61.958 LMS_LASER_2D_RIGHT LMS2 ID=3924,time=1225719873.600577,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=13,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.501,-1.000,15.492,12.799,10.971,9.856,8.918,8.022,7.342,6.811,6.289,5.869,5.459,5.112,4.800,4.509,4.300,4.064,3.845,3.681,3.486,3.351,3.192,3.053,2.924,2.822,2.696,2.606,2.516,2.415,2.336,2.250,2.195,2.125,2.064,1.993,1.953,1.902,1.850,1.815,1.771,1.708,1.687,1.652,1.613,1.572,1.555,1.533,1.477,1.434,1.411,1.366,1.371,1.359,1.340,1.306,1.284,1.265,1.262,1.254,1.242,1.241,1.265,1.264,1.268,1.271,1.271,1.239,1.236,1.226,1.216,1.209,1.188,1.167,1.138,1.130,1.133,1.110,1.107,1.116,1.105,1.103,1.085,1.075,1.067,1.058,1.050,1.043,1.016,1.008,0.981,0.991,0.957},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,16.000,0.000,122.000,108.000,83.000,64.000,58.000,60.000,58.000,63.000,66.000,67.000,68.000,70.000,71.000,72.000,72.000,74.000,74.000,76.000,80.000,81.000,76.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,78.000,74.000,78.000,76.000,78.000,79.000,79.000,78.000,77.000,77.000,68.000,69.000,77.000,72.000,70.000,73.000,75.000,77.000,79.000,79.000,75.000,69.000,58.000,54.000,48.000,53.000,53.000,65.000,62.000,57.000,56.000,53.000,52.000,46.000,45.000,45.000,38.000,30.000,29.000,34.000,42.000,42.000,41.000,43.000,43.000,43.000,41.000,41.000,31.000,30.000,27.000,31.000,28.000}
-61.959 LMS_LASER_2D_LEFT LMS1 ID=4052,time=1225719873.608384,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=49,Range=[181]{1.050,1.048,1.055,1.068,1.078,1.082,1.104,1.109,1.119,1.132,1.143,1.144,1.161,1.178,1.187,1.204,1.228,1.241,1.239,1.259,1.280,1.300,1.308,1.326,1.344,1.363,1.372,1.391,1.424,1.432,1.458,1.479,1.503,1.528,1.547,1.573,1.591,1.622,1.643,1.677,1.708,1.741,1.780,1.807,1.841,1.883,1.929,1.973,2.007,2.054,2.103,2.152,2.208,2.258,2.305,2.358,2.418,2.487,2.534,2.611,2.693,2.740,2.830,2.909,2.962,2.954,2.986,3.137,3.265,3.360,3.532,3.653,3.738,3.961,4.086,4.226,4.201,4.199,4.199,4.195,4.190,4.194,4.193,4.198,4.234,4.346,4.430,4.473,4.487,4.483,4.531,4.525,4.528,4.517,4.526,4.526,4.531,4.529,4.532,4.541,4.541,4.544,4.551,4.561,4.558,4.570,4.574,4.589,4.591,4.599,4.599,4.611,4.623,4.641,4.641,4.655,4.660,4.663,3.894,3.572,3.567,3.476,4.735,4.752,4.761,4.778,3.870,3.892,4.830,4.841,4.856,3.717,3.545,3.560,3.542,3.583,4.971,3.511,3.354,3.217,3.176,3.001,3.029,2.884,2.816,2.794,2.614,2.581,2.592,2.560,2.541,2.562,2.453,2.343,2.256,2.243,2.259,2.059,2.050,2.058,2.101,2.085,2.116,2.288,2.350,5.727,5.710,5.794,5.930,5.969,2.747,6.058,2.638,6.177,6.220,6.265,6.327,6.372,2.318,2.301,2.299},Reflectance=[181]{44.000,46.000,46.000,45.000,43.000,46.000,49.000,46.000,44.000,47.000,46.000,45.000,44.000,47.000,45.000,48.000,48.000,50.000,45.000,46.000,46.000,48.000,52.000,53.000,53.000,49.000,53.000,54.000,54.000,53.000,53.000,55.000,54.000,53.000,54.000,54.000,59.000,57.000,59.000,58.000,59.000,54.000,61.000,61.000,60.000,58.000,55.000,60.000,59.000,62.000,61.000,60.000,61.000,59.000,61.000,62.000,61.000,64.000,62.000,59.000,54.000,61.000,61.000,58.000,59.000,66.000,59.000,50.000,49.000,53.000,46.000,50.000,56.000,61.000,65.000,63.000,66.000,68.000,68.000,60.000,57.000,59.000,59.000,56.000,53.000,64.000,73.000,75.000,76.000,75.000,76.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,76.000,76.000,76.000,78.000,77.000,77.000,76.000,77.000,75.000,75.000,75.000,75.000,75.000,76.000,74.000,74.000,75.000,76.000,77.000,76.000,101.000,103.000,98.000,12.000,76.000,76.000,76.000,76.000,94.000,99.000,76.000,77.000,76.000,110.000,87.000,101.000,101.000,106.000,75.000,107.000,92.000,69.000,113.000,87.000,103.000,106.000,69.000,75.000,76.000,74.000,74.000,73.000,73.000,76.000,78.000,74.000,74.000,75.000,78.000,74.000,72.000,74.000,75.000,72.000,74.000,73.000,49.000,68.000,67.000,65.000,62.000,64.000,19.000,65.000,25.000,69.000,68.000,67.000,67.000,65.000,22.000,54.000,53.000}
-61.999 DESIRED_THRUST iJoystick 85.5708487197
-61.999 DESIRED_RUDDER iJoystick 1.02847376934
-61.969 LMS_LASER_2D_RIGHT LMS2 ID=3925,time=1225719873.613917,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=14,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.423,20.482,15.724,12.887,11.015,9.909,8.956,8.069,7.385,6.846,6.315,5.878,5.478,5.147,4.808,4.518,4.300,4.074,3.863,3.703,3.494,3.356,3.195,3.069,2.942,2.831,2.696,2.597,2.525,2.423,2.328,2.275,2.202,2.132,2.072,2.010,1.953,1.901,1.850,1.824,1.787,1.726,1.687,1.659,1.631,1.580,1.553,1.527,1.502,1.454,1.409,1.360,1.369,1.360,1.338,1.319,1.295,1.275,1.267,1.249,1.239,1.234,1.244,1.260,1.259,1.271,1.247,1.242,1.235,1.226,1.218,1.213,1.196,1.169,1.144,1.140,1.142,1.135,1.122,1.081,1.087,1.100,1.087,1.078,1.074,1.063,1.053,1.044,1.034,1.011,1.012,1.013,1.002},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,5.000,119.000,112.000,85.000,64.000,59.000,61.000,58.000,63.000,66.000,67.000,69.000,69.000,70.000,72.000,72.000,74.000,75.000,75.000,77.000,79.000,73.000,79.000,81.000,81.000,80.000,81.000,81.000,80.000,80.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,77.000,77.000,78.000,78.000,78.000,79.000,79.000,77.000,74.000,69.000,65.000,74.000,76.000,76.000,75.000,75.000,76.000,78.000,78.000,78.000,75.000,69.000,61.000,56.000,56.000,53.000,63.000,70.000,61.000,57.000,57.000,55.000,51.000,47.000,44.000,46.000,43.000,33.000,32.000,27.000,30.000,41.000,45.000,45.000,43.000,42.000,39.000,42.000,36.000,30.000,34.000,38.000,33.000}
-61.982 LMS_LASER_2D_RIGHT LMS2 ID=3926,time=1225719873.627257,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=15,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.524,-1.000,15.932,12.976,11.106,9.993,9.019,8.194,7.444,6.891,6.375,5.886,5.511,5.138,4.837,4.535,4.321,4.082,3.887,3.704,3.518,3.341,3.177,3.080,2.949,2.840,2.714,2.614,2.532,2.434,2.335,2.267,2.211,2.142,2.080,2.011,1.961,1.918,1.866,1.824,1.785,1.731,1.687,1.653,1.620,1.586,1.552,1.527,1.499,1.460,1.400,1.381,1.391,1.370,1.343,1.315,1.298,1.280,1.259,1.251,1.244,1.250,1.258,1.266,1.266,1.273,1.249,1.235,1.246,1.229,1.219,1.213,1.202,1.171,1.149,1.134,1.138,1.120,1.094,1.080,1.109,1.103,1.085,1.077,1.067,1.061,1.045,1.040,1.032,1.013,1.013,1.009,0.988},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,0.000,114.000,114.000,85.000,64.000,60.000,58.000,58.000,63.000,66.000,68.000,69.000,69.000,70.000,71.000,72.000,74.000,74.000,76.000,76.000,78.000,74.000,80.000,80.000,81.000,80.000,80.000,80.000,81.000,80.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,73.000,70.000,63.000,65.000,74.000,75.000,77.000,77.000,74.000,77.000,76.000,78.000,78.000,76.000,68.000,60.000,51.000,51.000,54.000,67.000,71.000,58.000,54.000,58.000,59.000,54.000,52.000,42.000,47.000,45.000,32.000,26.000,27.000,33.000,42.000,41.000,44.000,43.000,44.000,40.000,38.000,36.000,32.000,32.000,35.000,31.000}
-61.982 LMS_LASER_2D_LEFT LMS1 ID=4053,time=1225719873.621729,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=50,Range=[181]{1.052,1.051,1.052,1.061,1.077,1.078,1.095,1.102,1.119,1.120,1.137,1.164,1.161,1.179,1.194,1.205,1.223,1.236,1.243,1.263,1.283,1.293,1.308,1.318,1.338,1.363,1.374,1.398,1.420,1.433,1.450,1.489,1.504,1.528,1.546,1.569,1.593,1.624,1.647,1.685,1.715,1.745,1.777,1.799,1.841,1.883,1.926,1.965,2.005,2.060,2.096,2.146,2.205,2.251,2.303,2.351,2.417,2.478,2.535,2.594,2.676,2.749,2.822,2.884,2.953,2.947,2.980,3.132,3.226,3.358,3.514,3.640,3.736,3.923,4.063,4.203,4.195,4.194,4.186,4.183,4.185,4.189,4.199,4.268,4.369,4.384,4.425,4.461,4.486,4.474,4.518,4.516,4.515,4.516,4.517,4.518,4.524,4.529,4.532,4.532,4.533,4.543,4.541,4.549,4.556,4.557,4.573,4.579,4.580,4.592,4.600,4.609,4.624,4.633,4.641,4.654,4.658,4.667,3.755,3.740,3.692,3.487,4.734,4.742,4.761,4.019,3.854,4.793,4.813,4.831,4.849,3.611,3.520,3.483,3.465,3.479,3.347,3.321,3.330,3.212,3.026,2.939,2.912,2.989,2.944,2.896,2.594,2.551,2.565,2.579,2.617,2.383,2.290,2.260,2.256,2.197,2.013,2.011,2.022,2.032,2.045,2.065,2.087,2.152,2.250,2.565,2.497,5.761,5.919,2.776,2.745,2.744,2.652,6.166,6.209,6.252,6.313,6.361,2.326,2.286,2.284},Reflectance=[181]{42.000,44.000,46.000,45.000,45.000,46.000,46.000,43.000,45.000,46.000,45.000,38.000,43.000,48.000,48.000,49.000,47.000,48.000,46.000,48.000,49.000,49.000,52.000,53.000,54.000,53.000,54.000,53.000,52.000,54.000,53.000,51.000,54.000,53.000,58.000,56.000,55.000,58.000,61.000,57.000,58.000,56.000,59.000,61.000,60.000,58.000,58.000,60.000,58.000,61.000,62.000,61.000,60.000,61.000,60.000,63.000,60.000,60.000,63.000,60.000,55.000,61.000,62.000,63.000,59.000,64.000,60.000,48.000,56.000,51.000,48.000,52.000,60.000,63.000,69.000,67.000,64.000,69.000,67.000,63.000,59.000,56.000,53.000,57.000,71.000,76.000,75.000,75.000,76.000,75.000,75.000,77.000,77.000,77.000,77.000,78.000,77.000,76.000,76.000,76.000,77.000,77.000,76.000,76.000,76.000,76.000,75.000,74.000,75.000,75.000,75.000,75.000,75.000,75.000,75.000,76.000,77.000,77.000,103.000,106.000,103.000,22.000,76.000,76.000,76.000,98.000,95.000,76.000,77.000,77.000,77.000,105.000,84.000,75.000,75.000,87.000,33.000,30.000,99.000,73.000,99.000,79.000,74.000,98.000,105.000,101.000,75.000,76.000,75.000,68.000,74.000,85.000,74.000,73.000,74.000,77.000,68.000,73.000,73.000,74.000,75.000,71.000,68.000,72.000,70.000,38.000,27.000,65.000,61.000,56.000,58.000,40.000,34.000,68.000,67.000,66.000,65.000,64.000,37.000,64.000,72.000}
-61.993 LMS_LASER_2D_RIGHT LMS2 ID=3927,time=1225719873.640595,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=16,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.512,-1.000,16.075,13.208,11.266,10.071,9.112,8.293,7.504,6.951,6.426,5.972,5.553,5.184,4.881,4.552,4.331,4.102,3.888,3.719,3.545,3.363,3.177,3.104,2.959,2.840,2.723,2.626,2.543,2.443,2.335,2.274,2.203,2.150,2.089,2.027,1.967,1.927,1.875,1.832,1.786,1.750,1.688,1.645,1.613,1.577,1.566,1.533,1.499,1.464,1.423,1.414,1.405,1.379,1.348,1.311,1.298,1.274,1.260,1.254,1.249,1.242,1.252,1.262,1.280,1.265,1.262,1.262,1.249,1.232,1.216,1.215,1.192,1.180,1.153,1.141,1.144,1.127,1.094,1.081,1.075,1.097,1.093,1.084,1.070,1.061,1.050,1.040,1.026,1.016,1.012,1.013,1.007},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,0.000,111.000,117.000,89.000,67.000,59.000,58.000,57.000,62.000,66.000,67.000,68.000,69.000,71.000,72.000,72.000,74.000,75.000,75.000,75.000,77.000,74.000,79.000,81.000,81.000,80.000,80.000,81.000,81.000,80.000,80.000,81.000,81.000,81.000,80.000,79.000,80.000,80.000,80.000,79.000,79.000,79.000,74.000,76.000,78.000,77.000,68.000,70.000,71.000,73.000,74.000,76.000,77.000,76.000,75.000,76.000,77.000,78.000,79.000,78.000,70.000,61.000,53.000,46.000,54.000,57.000,61.000,60.000,56.000,60.000,60.000,61.000,56.000,44.000,46.000,44.000,32.000,27.000,25.000,28.000,37.000,39.000,43.000,44.000,44.000,41.000,36.000,35.000,31.000,34.000,38.000,34.000}
-61.994 LMS_LASER_2D_LEFT LMS1 ID=4054,time=1225719873.635072,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=51,Range=[181]{1.055,1.042,1.063,1.069,1.080,1.085,1.094,1.116,1.120,1.119,1.131,1.154,1.168,1.173,1.178,1.197,1.213,1.231,1.242,1.259,1.279,1.289,1.301,1.321,1.342,1.364,1.373,1.399,1.417,1.433,1.450,1.476,1.494,1.530,1.545,1.574,1.586,1.619,1.649,1.679,1.710,1.729,1.769,1.805,1.833,1.878,1.925,1.965,2.004,2.050,2.098,2.152,2.196,2.252,2.308,2.357,2.411,2.472,2.531,2.587,2.679,2.757,2.814,2.898,2.926,2.945,2.965,3.125,3.221,3.339,3.497,3.614,3.765,3.897,4.044,4.195,4.189,4.189,4.182,4.201,4.243,4.326,4.334,4.382,4.397,4.376,4.416,4.453,4.476,4.474,4.511,4.516,4.507,4.514,4.514,4.515,4.515,4.520,4.522,4.523,4.533,4.535,4.537,4.549,4.547,4.556,4.562,4.573,4.580,4.589,4.597,4.599,4.608,4.626,4.633,4.646,4.649,3.793,3.565,3.497,3.565,4.720,4.726,4.742,4.752,3.968,3.970,4.796,4.812,4.832,4.840,3.513,3.576,3.503,3.481,3.494,3.353,3.480,3.233,3.183,3.160,3.047,2.904,2.922,3.016,2.884,2.547,2.550,2.564,2.606,2.571,2.311,2.301,2.342,2.340,2.134,2.029,2.023,2.011,1.982,2.001,2.054,2.084,2.111,2.194,2.539,2.543,2.534,2.794,2.764,2.750,2.673,2.665,6.147,6.196,6.243,6.297,6.348,6.402,2.227,2.258},Reflectance=[181]{41.000,44.000,41.000,43.000,41.000,43.000,45.000,41.000,43.000,45.000,46.000,48.000,46.000,46.000,45.000,47.000,45.000,47.000,46.000,47.000,51.000,51.000,53.000,50.000,52.000,54.000,54.000,53.000,54.000,54.000,53.000,53.000,54.000,54.000,53.000,59.000,61.000,56.000,57.000,59.000,56.000,62.000,59.000,59.000,61.000,60.000,57.000,56.000,58.000,60.000,58.000,60.000,60.000,56.000,58.000,61.000,61.000,61.000,61.000,61.000,56.000,55.000,62.000,65.000,63.000,59.000,56.000,47.000,49.000,51.000,49.000,45.000,49.000,66.000,69.000,67.000,65.000,65.000,62.000,58.000,53.000,59.000,66.000,75.000,77.000,76.000,74.000,75.000,76.000,75.000,76.000,77.000,77.000,76.000,76.000,77.000,77.000,76.000,76.000,76.000,77.000,77.000,78.000,76.000,76.000,76.000,74.000,75.000,74.000,75.000,75.000,75.000,75.000,75.000,75.000,76.000,77.000,104.000,91.000,77.000,96.000,77.000,76.000,76.000,76.000,98.000,100.000,77.000,76.000,77.000,77.000,26.000,99.000,81.000,77.000,99.000,37.000,110.000,93.000,90.000,39.000,120.000,74.000,75.000,98.000,58.000,74.000,75.000,74.000,73.000,65.000,75.000,74.000,86.000,80.000,84.000,73.000,76.000,75.000,74.000,70.000,68.000,67.000,69.000,72.000,47.000,21.000,19.000,32.000,72.000,73.000,63.000,49.000,67.000,69.000,66.000,66.000,65.000,63.000,28.000,50.000}
-61.999 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.3401,18.6607,-0.7989},Vel=[3x1]{-0.7963,-0.7751,7.3077},Raw=[2x1]{20.1637,-0.7989},time=1225719873.64642930030823,Speed=1.11124091002015,Pitch=0.00448670746768,Roll=0.04486707467677,PitchDot=0.03589365974142,RollDot=-0.00058327197080
-61.999 ODOMETRY_POSE iPlatform Pose=[3x1]{4.3401,18.6607,-0.7983},Vel=[3x1]{-0.7963,-0.7751,1.0248},Raw=[2x1]{20.1637,-0.7989},time=1225719873.6464,Speed=1.1112,Pitch=-0.0290,Roll=0.0345,PitchDot=0.0181,RollDot=-0.0310
-62.007 LMS_LASER_2D_LEFT LMS1 ID=4055,time=1225719873.648415,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=52,Range=[181]{1.052,1.063,1.064,1.078,1.084,1.092,1.098,1.115,1.111,1.128,1.146,1.154,1.162,1.182,1.189,1.208,1.225,1.236,1.244,1.260,1.275,1.289,1.309,1.320,1.345,1.357,1.373,1.391,1.416,1.431,1.450,1.476,1.502,1.520,1.547,1.573,1.588,1.623,1.645,1.672,1.696,1.727,1.762,1.797,1.829,1.873,1.915,1.962,2.005,2.047,2.088,2.144,2.189,2.244,2.294,2.350,2.395,2.464,2.532,2.594,2.680,2.763,2.818,2.893,2.923,2.948,2.974,3.103,3.220,3.362,3.498,3.619,3.759,3.891,4.031,4.212,4.236,4.278,4.301,4.346,4.377,4.380,4.372,4.378,4.396,4.377,4.407,4.451,4.476,4.467,4.502,4.514,4.508,4.498,4.503,4.515,4.507,4.513,4.511,4.523,4.525,4.526,4.535,4.541,4.546,4.548,4.554,4.567,4.573,4.584,4.584,4.600,4.603,4.619,4.626,4.636,4.649,3.651,3.499,3.486,3.598,4.706,4.714,4.727,4.744,3.671,4.768,4.787,4.796,4.821,4.833,4.840,4.867,3.666,3.504,3.411,3.376,3.364,2.988,2.966,3.035,3.029,2.998,3.014,3.082,2.966,2.915,2.584,2.617,2.674,2.669,2.695,2.711,2.712,2.468,2.390,2.043,2.029,2.037,1.972,1.974,2.063,2.100,2.131,2.156,2.246,2.525,2.555,2.771,2.724,2.746,2.582,2.566,2.589,6.186,6.227,6.289,6.332,6.390,5.154,5.194},Reflectance=[181]{40.000,40.000,45.000,40.000,43.000,43.000,45.000,45.000,47.000,47.000,44.000,48.000,48.000,45.000,46.000,42.000,46.000,48.000,51.000,50.000,46.000,52.000,49.000,46.000,49.000,50.000,54.000,54.000,54.000,53.000,53.000,53.000,53.000,54.000,54.000,54.000,57.000,58.000,55.000,60.000,58.000,56.000,61.000,60.000,58.000,57.000,56.000,58.000,58.000,58.000,62.000,60.000,56.000,61.000,59.000,62.000,62.000,62.000,61.000,60.000,56.000,54.000,55.000,66.000,65.000,56.000,56.000,56.000,47.000,49.000,49.000,47.000,45.000,64.000,70.000,60.000,59.000,58.000,61.000,72.000,76.000,77.000,77.000,76.000,76.000,76.000,74.000,74.000,76.000,76.000,76.000,76.000,78.000,77.000,76.000,77.000,77.000,76.000,76.000,76.000,77.000,78.000,77.000,76.000,75.000,76.000,75.000,76.000,75.000,76.000,73.000,73.000,76.000,76.000,75.000,75.000,77.000,100.000,74.000,76.000,102.000,78.000,78.000,76.000,76.000,10.000,76.000,77.000,77.000,76.000,78.000,77.000,78.000,113.000,15.000,29.000,30.000,99.000,74.000,75.000,101.000,103.000,100.000,113.000,122.000,30.000,48.000,67.000,71.000,72.000,65.000,51.000,36.000,126.000,79.000,82.000,67.000,75.000,75.000,74.000,72.000,71.000,72.000,73.000,70.000,69.000,31.000,26.000,41.000,70.000,72.000,66.000,47.000,20.000,69.000,67.000,66.000,66.000,65.000,26.000,82.000}
-62.023 DESIRED_THRUST iJoystick 85.5708487197
-62.023 DESIRED_RUDDER iJoystick 1.02847376934
-62.006 LMS_LASER_2D_RIGHT LMS2 ID=3928,time=1225719873.653932,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=17,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.411,13.557,11.555,10.160,9.213,8.413,7.592,7.015,6.485,6.025,5.605,5.220,4.926,4.596,4.331,4.126,3.911,3.745,3.547,3.393,3.198,3.121,2.982,2.856,2.743,2.633,2.552,2.444,2.354,2.293,2.221,2.152,2.089,2.027,1.966,1.927,1.886,1.841,1.785,1.762,1.707,1.660,1.619,1.594,1.571,1.536,1.503,1.485,1.459,1.431,1.402,1.365,1.339,1.312,1.294,1.271,1.261,1.260,1.247,1.244,1.248,1.259,1.270,1.266,1.275,1.270,1.261,1.246,1.223,1.213,1.204,1.188,1.160,1.143,1.138,1.125,1.094,1.087,1.090,1.101,1.093,1.084,1.071,1.064,1.057,1.039,1.029,0.988,1.017,1.013,1.004},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,101.000,116.000,88.000,71.000,59.000,57.000,56.000,61.000,67.000,67.000,68.000,69.000,70.000,72.000,73.000,74.000,73.000,75.000,76.000,77.000,80.000,79.000,80.000,80.000,81.000,80.000,81.000,81.000,80.000,81.000,81.000,81.000,81.000,80.000,79.000,80.000,81.000,80.000,79.000,80.000,79.000,78.000,77.000,78.000,79.000,77.000,74.000,77.000,74.000,73.000,76.000,75.000,75.000,75.000,75.000,76.000,79.000,78.000,77.000,72.000,66.000,56.000,49.000,55.000,55.000,53.000,53.000,54.000,60.000,59.000,63.000,55.000,43.000,47.000,45.000,33.000,27.000,26.000,30.000,41.000,41.000,43.000,40.000,40.000,41.000,34.000,32.000,27.000,32.000,38.000,32.000}
-62.018 LMS_LASER_2D_RIGHT LMS2 ID=3929,time=1225719873.667267,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=18,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.856,13.860,11.812,10.276,9.329,8.538,7.678,7.075,6.572,6.079,5.671,5.256,4.972,4.639,4.349,4.146,3.929,3.762,3.602,3.432,3.225,3.131,2.999,2.873,2.755,2.653,2.560,2.461,2.373,2.304,2.241,2.160,2.099,2.054,1.978,1.935,1.895,1.838,1.786,1.759,1.717,1.662,1.616,1.598,1.572,1.544,1.515,1.495,1.468,1.431,1.395,1.378,1.354,1.330,1.306,1.283,1.271,1.257,1.254,1.244,1.257,1.262,1.265,1.273,1.274,1.272,1.274,1.257,1.223,1.221,1.196,1.185,1.156,1.147,1.140,1.137,1.093,1.082,1.092,1.103,1.095,1.086,1.076,1.068,1.054,1.039,1.031,1.005,0.988,1.008,1.002},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,88.000,118.000,90.000,76.000,60.000,56.000,58.000,59.000,66.000,67.000,67.000,70.000,70.000,72.000,73.000,75.000,74.000,75.000,77.000,77.000,80.000,79.000,80.000,80.000,81.000,80.000,80.000,81.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,81.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,74.000,72.000,72.000,76.000,77.000,75.000,74.000,75.000,77.000,78.000,77.000,74.000,64.000,57.000,54.000,54.000,47.000,50.000,43.000,43.000,56.000,55.000,64.000,58.000,45.000,45.000,46.000,35.000,28.000,26.000,29.000,42.000,45.000,42.000,43.000,44.000,40.000,34.000,31.000,29.000,27.000,32.000,33.000}
-62.018 LMS_LASER_2D_LEFT LMS1 ID=4056,time=1225719873.661756,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=53,Range=[181]{1.048,1.060,1.067,1.075,1.081,1.086,1.098,1.099,1.113,1.131,1.137,1.155,1.164,1.182,1.186,1.196,1.223,1.224,1.245,1.259,1.270,1.284,1.303,1.319,1.336,1.355,1.373,1.395,1.408,1.433,1.442,1.469,1.494,1.511,1.537,1.566,1.583,1.617,1.633,1.670,1.693,1.722,1.766,1.788,1.830,1.868,1.904,1.955,2.000,2.030,2.084,2.130,2.183,2.247,2.298,2.346,2.401,2.464,2.528,2.582,2.658,2.739,2.837,2.905,2.943,2.964,2.973,3.085,3.168,3.340,3.483,3.604,3.745,3.919,4.020,4.307,4.293,4.294,4.317,4.356,4.369,4.370,4.371,4.375,4.395,4.374,4.389,4.438,4.463,4.468,4.491,4.516,4.495,4.499,4.498,4.508,4.510,4.508,4.503,4.516,4.508,4.525,4.526,4.532,4.537,4.546,4.554,4.548,4.565,4.576,4.586,4.588,4.597,4.608,4.618,4.627,4.639,3.613,3.498,3.513,3.638,4.703,4.712,4.726,4.737,4.753,4.761,4.781,4.785,4.811,4.824,4.842,4.857,4.877,4.893,4.913,4.938,3.102,2.925,2.919,2.930,2.932,2.963,5.081,3.062,2.993,2.928,2.710,2.646,2.650,2.666,2.672,2.708,2.516,2.274,1.997,1.982,1.991,2.000,1.981,1.952,2.020,2.057,2.080,2.125,2.199,2.494,2.533,2.558,2.641,2.666,2.598,2.576,2.584,2.486,6.222,6.273,6.328,6.372,6.434,5.287},Reflectance=[181]{42.000,39.000,43.000,43.000,45.000,44.000,45.000,47.000,46.000,45.000,49.000,46.000,49.000,45.000,48.000,49.000,46.000,50.000,48.000,50.000,51.000,49.000,50.000,49.000,53.000,54.000,54.000,51.000,54.000,54.000,54.000,54.000,54.000,54.000,54.000,55.000,55.000,55.000,58.000,59.000,61.000,58.000,58.000,60.000,59.000,55.000,60.000,59.000,60.000,63.000,60.000,61.000,58.000,58.000,57.000,60.000,61.000,61.000,59.000,58.000,55.000,55.000,52.000,56.000,58.000,56.000,56.000,56.000,57.000,48.000,51.000,48.000,51.000,61.000,72.000,69.000,75.000,76.000,74.000,75.000,76.000,77.000,77.000,76.000,76.000,75.000,75.000,73.000,75.000,76.000,75.000,77.000,76.000,77.000,77.000,78.000,78.000,78.000,76.000,77.000,78.000,77.000,77.000,76.000,75.000,75.000,75.000,76.000,75.000,76.000,74.000,72.000,72.000,75.000,75.000,75.000,76.000,99.000,80.000,84.000,105.000,77.000,77.000,76.000,77.000,76.000,76.000,77.000,76.000,76.000,77.000,77.000,77.000,78.000,77.000,76.000,76.000,116.000,75.000,76.000,77.000,75.000,48.000,76.000,118.000,12.000,51.000,69.000,74.000,73.000,72.000,62.000,40.000,123.000,74.000,76.000,74.000,75.000,75.000,74.000,73.000,75.000,74.000,68.000,71.000,73.000,64.000,56.000,55.000,60.000,59.000,44.000,60.000,29.000,25.000,69.000,67.000,67.000,67.000,65.000,96.000}
-62.031 LMS_LASER_2D_LEFT LMS1 ID=4057,time=1225719873.675096,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=54,Range=[181]{1.050,1.052,1.064,1.067,1.084,1.090,1.096,1.107,1.118,1.131,1.136,1.157,1.161,1.179,1.192,1.208,1.216,1.225,1.238,1.248,1.273,1.278,1.304,1.317,1.333,1.337,1.364,1.390,1.409,1.424,1.443,1.455,1.476,1.504,1.531,1.553,1.586,1.616,1.628,1.667,1.688,1.714,1.762,1.787,1.818,1.864,1.911,1.946,1.987,2.038,2.075,2.122,2.176,2.239,2.279,2.327,2.400,2.455,2.515,2.578,2.668,2.746,2.820,2.892,2.926,2.939,2.954,3.057,3.149,3.276,3.463,3.591,3.716,3.916,3.995,4.304,4.294,4.292,4.299,4.346,4.355,4.367,4.370,4.367,4.386,4.365,4.387,4.433,4.456,4.459,4.474,4.516,4.497,4.490,4.496,4.499,4.502,4.499,4.497,4.508,4.506,4.514,4.517,4.525,4.529,4.543,4.543,4.547,4.558,4.564,4.571,4.578,4.592,4.602,4.608,4.618,3.926,3.492,3.418,3.499,3.576,3.614,4.703,4.716,4.729,4.744,4.755,4.773,4.780,4.796,4.807,4.833,4.850,4.867,4.884,4.909,4.923,3.116,3.015,2.932,2.931,2.928,2.974,2.985,3.039,2.920,2.797,2.758,2.660,2.644,2.638,2.649,2.552,2.426,2.165,2.014,1.961,1.962,1.963,1.996,1.956,1.988,2.065,2.070,2.115,2.152,2.242,2.524,2.547,2.510,2.502,2.581,2.576,2.659,2.512,2.470,6.254,6.312,6.362,6.418,5.289},Reflectance=[181]{38.000,44.000,45.000,48.000,43.000,45.000,46.000,46.000,48.000,45.000,44.000,45.000,48.000,44.000,47.000,45.000,45.000,46.000,49.000,49.000,49.000,51.000,47.000,49.000,48.000,53.000,53.000,53.000,54.000,53.000,54.000,56.000,58.000,54.000,55.000,57.000,56.000,54.000,61.000,57.000,58.000,63.000,61.000,67.000,61.000,61.000,59.000,59.000,62.000,58.000,60.000,62.000,59.000,54.000,61.000,59.000,60.000,61.000,61.000,56.000,51.000,54.000,51.000,53.000,63.000,56.000,55.000,55.000,65.000,50.000,46.000,50.000,50.000,60.000,72.000,70.000,76.000,75.000,75.000,75.000,75.000,76.000,77.000,76.000,76.000,75.000,74.000,74.000,75.000,76.000,75.000,77.000,77.000,78.000,76.000,77.000,78.000,78.000,77.000,78.000,77.000,76.000,77.000,77.000,76.000,75.000,74.000,76.000,76.000,75.000,69.000,69.000,68.000,76.000,75.000,75.000,98.000,83.000,75.000,87.000,98.000,108.000,77.000,76.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,77.000,76.000,123.000,98.000,77.000,77.000,74.000,42.000,46.000,105.000,47.000,58.000,56.000,56.000,74.000,75.000,75.000,79.000,77.000,83.000,84.000,73.000,74.000,74.000,70.000,72.000,74.000,79.000,73.000,73.000,76.000,83.000,73.000,72.000,58.000,54.000,58.000,55.000,5.000,55.000,17.000,67.000,68.000,67.000,65.000,97.000}
-62.035 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.3719,18.6916,-0.8029},Vel=[3x1]{-0.7973,-0.7698,6.6667},Raw=[2x1]{20.2081,-0.8029},time=1225719873.68238520622253,Speed=1.10832043456675,Pitch=0.00448670746768,Roll=0.04262372094293,PitchDot=0.01570347613687,RollDot=-0.00058327197080
-62.035 ODOMETRY_POSE iPlatform Pose=[3x1]{4.3719,18.6916,-0.8024},Vel=[3x1]{-0.7973,-0.7698,0.3836},Raw=[2x1]{20.2081,-0.8029},time=1225719873.6824,Speed=1.1083,Pitch=-0.0275,Roll=0.0328,PitchDot=0.0143,RollDot=-0.0064
-62.047 DESIRED_THRUST iJoystick 85.5708487197
-62.047 DESIRED_RUDDER iJoystick 1.02847376934
-62.030 LMS_LASER_2D_RIGHT LMS2 ID=3930,time=1225719873.680601,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=19,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.256,14.233,12.174,10.501,9.469,8.688,7.787,7.163,6.670,6.163,5.749,5.328,5.007,4.689,4.376,4.207,3.964,3.776,3.632,3.465,3.254,3.171,3.027,2.881,2.772,2.676,2.568,2.468,2.389,2.330,2.258,2.184,2.123,2.062,2.003,1.944,1.902,1.855,1.794,1.751,1.707,1.671,1.635,1.607,1.572,1.553,1.525,1.500,1.477,1.423,1.396,1.379,1.360,1.339,1.306,1.289,1.279,1.263,1.253,1.243,1.249,1.266,1.270,1.278,1.295,1.282,1.273,1.252,1.230,1.222,1.197,1.188,1.169,1.159,1.150,1.139,1.104,1.087,1.098,1.111,1.102,1.087,1.083,1.075,1.057,1.048,1.029,0.999,1.006,1.012,0.991},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,80.000,119.000,91.000,79.000,62.000,56.000,60.000,59.000,65.000,66.000,67.000,69.000,69.000,72.000,74.000,75.000,74.000,74.000,75.000,76.000,81.000,80.000,80.000,80.000,81.000,79.000,80.000,80.000,80.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,77.000,76.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,77.000,72.000,74.000,77.000,77.000,75.000,73.000,74.000,76.000,77.000,76.000,72.000,67.000,59.000,57.000,52.000,44.000,41.000,47.000,52.000,55.000,59.000,66.000,60.000,47.000,43.000,41.000,34.000,28.000,26.000,29.000,41.000,44.000,44.000,43.000,43.000,36.000,36.000,31.000,29.000,30.000,34.000,30.000}
-62.042 LMS_LASER_2D_LEFT LMS1 ID=4058,time=1225719873.688433,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=55,Range=[181]{1.044,1.054,1.065,1.071,1.081,1.081,1.100,1.099,1.111,1.132,1.134,1.152,1.166,1.178,1.183,1.197,1.213,1.220,1.240,1.251,1.266,1.284,1.294,1.318,1.328,1.347,1.370,1.382,1.399,1.416,1.438,1.454,1.476,1.509,1.530,1.555,1.580,1.603,1.629,1.660,1.690,1.718,1.750,1.783,1.806,1.853,1.901,1.944,1.994,2.020,2.071,2.123,2.175,2.226,2.276,2.324,2.389,2.443,2.507,2.568,2.661,2.727,2.812,2.877,2.931,2.948,2.958,3.045,3.176,3.273,3.397,3.568,3.680,3.847,3.966,4.239,4.289,4.284,4.292,4.338,4.347,4.356,4.367,4.355,4.382,4.370,4.375,4.415,4.448,4.452,4.456,4.510,4.495,4.481,4.490,4.490,4.492,4.500,4.505,4.507,4.507,4.514,4.517,4.517,4.523,4.529,4.536,4.540,4.547,4.554,4.569,4.577,4.586,4.592,4.599,4.609,3.739,3.488,3.449,3.495,3.720,3.595,3.606,4.712,4.726,4.736,4.745,4.762,4.780,4.788,4.798,4.825,4.842,4.859,4.878,4.894,4.916,4.937,3.019,3.082,2.976,3.041,3.028,2.857,2.802,2.709,2.747,2.786,2.618,2.642,2.635,2.592,2.520,2.546,2.016,1.893,1.885,1.895,1.895,1.903,1.871,1.959,2.063,2.153,2.186,2.117,2.178,2.502,2.509,2.519,2.481,2.479,2.489,2.579,2.551,2.531,6.258,6.317,6.370,6.420,5.162},Reflectance=[181]{40.000,41.000,42.000,41.000,41.000,46.000,42.000,47.000,48.000,45.000,47.000,43.000,45.000,44.000,47.000,49.000,49.000,51.000,49.000,46.000,50.000,53.000,54.000,49.000,49.000,50.000,52.000,53.000,53.000,53.000,56.000,55.000,57.000,56.000,54.000,58.000,53.000,56.000,55.000,58.000,59.000,60.000,59.000,62.000,64.000,61.000,57.000,58.000,56.000,62.000,58.000,57.000,58.000,56.000,59.000,58.000,59.000,60.000,61.000,55.000,48.000,50.000,55.000,54.000,56.000,56.000,56.000,49.000,52.000,49.000,46.000,44.000,49.000,66.000,71.000,70.000,74.000,75.000,75.000,75.000,75.000,75.000,76.000,75.000,75.000,74.000,73.000,74.000,76.000,77.000,75.000,75.000,76.000,78.000,77.000,78.000,78.000,78.000,76.000,77.000,77.000,76.000,77.000,78.000,76.000,73.000,75.000,76.000,76.000,75.000,71.000,69.000,71.000,75.000,75.000,75.000,96.000,71.000,81.000,86.000,104.000,107.000,110.000,77.000,76.000,76.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,75.000,39.000,97.000,75.000,98.000,34.000,114.000,104.000,66.000,72.000,48.000,30.000,73.000,76.000,77.000,75.000,74.000,92.000,74.000,74.000,74.000,75.000,74.000,70.000,78.000,80.000,79.000,82.000,74.000,77.000,74.000,74.000,72.000,68.000,70.000,56.000,56.000,56.000,24.000,65.000,67.000,67.000,63.000,80.000}
-62.054 LMS_LASER_2D_LEFT LMS1 ID=4059,time=1225719873.701770,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=56,Range=[181]{1.044,1.047,1.058,1.067,1.075,1.081,1.097,1.107,1.115,1.119,1.135,1.149,1.154,1.166,1.185,1.192,1.202,1.225,1.234,1.244,1.263,1.278,1.298,1.303,1.334,1.339,1.368,1.382,1.392,1.425,1.434,1.469,1.477,1.506,1.524,1.546,1.581,1.599,1.622,1.657,1.686,1.709,1.748,1.783,1.810,1.856,1.883,1.932,1.976,2.017,2.060,2.111,2.164,2.214,2.262,2.320,2.387,2.440,2.504,2.559,2.659,2.727,2.793,2.831,2.921,2.929,2.937,3.009,3.163,3.273,3.377,3.536,3.652,3.811,3.951,4.122,4.283,4.283,4.283,4.318,4.346,4.351,4.357,4.357,4.371,4.365,4.362,4.400,4.434,4.443,4.449,4.501,4.502,4.480,4.481,4.480,4.483,4.483,4.490,4.492,4.500,4.497,4.499,4.509,4.517,4.517,4.523,4.535,4.544,4.550,4.562,4.563,4.579,4.591,4.592,4.608,3.841,3.723,3.436,3.693,3.398,3.439,3.541,3.569,4.716,4.725,3.209,3.247,4.770,4.779,4.790,4.808,4.826,4.844,4.868,4.885,4.901,4.929,3.032,3.099,3.004,3.067,2.849,2.682,2.682,2.686,2.661,2.660,2.619,2.605,2.645,2.619,2.549,2.047,1.876,1.867,1.875,1.885,1.895,1.895,1.876,1.868,2.035,2.563,2.544,2.154,2.191,2.486,2.496,2.531,2.525,2.502,2.466,2.506,2.572,2.573,2.564,6.338,6.383,5.160,5.227},Reflectance=[181]{40.000,45.000,43.000,43.000,43.000,45.000,41.000,42.000,45.000,48.000,48.000,46.000,44.000,46.000,43.000,51.000,48.000,45.000,47.000,51.000,48.000,51.000,48.000,50.000,48.000,50.000,51.000,53.000,54.000,54.000,54.000,54.000,53.000,55.000,59.000,57.000,53.000,58.000,56.000,56.000,61.000,59.000,61.000,65.000,56.000,56.000,61.000,60.000,61.000,59.000,59.000,59.000,56.000,59.000,60.000,58.000,57.000,58.000,59.000,55.000,47.000,42.000,55.000,61.000,55.000,55.000,55.000,57.000,46.000,52.000,52.000,46.000,45.000,61.000,69.000,71.000,72.000,75.000,75.000,74.000,75.000,76.000,76.000,76.000,75.000,75.000,75.000,72.000,75.000,77.000,76.000,75.000,76.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,76.000,77.000,77.000,76.000,74.000,67.000,69.000,75.000,75.000,75.000,100.000,98.000,21.000,104.000,26.000,13.000,107.000,109.000,76.000,76.000,29.000,15.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,29.000,98.000,81.000,99.000,115.000,77.000,77.000,75.000,68.000,60.000,54.000,65.000,74.000,75.000,75.000,88.000,76.000,74.000,74.000,74.000,74.000,74.000,74.000,64.000,82.000,76.000,76.000,80.000,81.000,75.000,75.000,72.000,70.000,74.000,69.000,56.000,57.000,58.000,46.000,65.000,68.000,13.000,90.000}
-62.071 DESIRED_THRUST iJoystick 85.5708487197
-62.071 DESIRED_RUDDER iJoystick 1.02847376934
-62.071 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.3961,18.7148,-0.8061},Vel=[3x1]{-0.8029,-0.7703,7.4359},Raw=[2x1]{20.2416,-0.8061},time=1225719873.71844315528870,Speed=1.11270114774685,Pitch=0.00224335373384,Roll=0.04038036720910,PitchDot=0.00448670746768,RollDot=-0.00089734149354
-62.071 ODOMETRY_POSE iPlatform Pose=[3x1]{4.3961,18.7148,-0.8056},Vel=[3x1]{-0.8029,-0.7703,1.1527},Raw=[2x1]{20.2416,-0.8061},time=1225719873.7184,Speed=1.1127,Pitch=-0.0276,Roll=0.0296,PitchDot=0.0010,RollDot=-0.0045
-62.055 LMS_LASER_2D_RIGHT LMS2 ID=3931,time=1225719873.693947,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=20,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.094,18.243,14.917,12.507,10.807,9.630,8.835,7.905,7.267,6.776,6.245,5.812,5.381,5.058,4.782,4.399,4.256,3.981,3.829,3.663,3.489,3.332,3.203,3.060,2.907,2.790,2.688,2.584,2.468,2.407,2.329,2.267,2.192,2.131,2.071,2.012,1.962,1.910,1.863,1.812,1.747,1.707,1.677,1.643,1.607,1.580,1.563,1.531,1.510,1.469,1.440,1.414,1.385,1.360,1.336,1.314,1.289,1.279,1.265,1.257,1.247,1.250,1.265,1.273,1.275,1.284,1.289,1.269,1.238,1.238,1.231,1.205,1.191,1.182,1.165,1.150,1.141,1.127,1.091,1.084,1.117,1.105,1.096,1.079,1.073,1.059,1.051,1.007,1.023,1.027,1.012,1.002},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,83.000,118.000,97.000,80.000,65.000,56.000,60.000,59.000,64.000,66.000,67.000,69.000,68.000,70.000,75.000,76.000,74.000,75.000,76.000,76.000,78.000,79.000,79.000,80.000,81.000,80.000,79.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,81.000,80.000,80.000,79.000,79.000,76.000,74.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,77.000,73.000,73.000,76.000,73.000,75.000,76.000,74.000,76.000,77.000,78.000,75.000,68.000,58.000,54.000,51.000,48.000,40.000,48.000,64.000,58.000,51.000,59.000,61.000,52.000,40.000,38.000,32.000,30.000,26.000,28.000,41.000,45.000,45.000,40.000,46.000,41.000,36.000,28.000,30.000,35.000,31.000,32.000}
-62.066 LMS_LASER_2D_LEFT LMS1 ID=4060,time=1225719873.715105,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=57,Range=[181]{1.046,1.047,1.050,1.056,1.076,1.080,1.085,1.104,1.115,1.124,1.132,1.140,1.154,1.161,1.185,1.200,1.201,1.217,1.233,1.247,1.262,1.276,1.290,1.307,1.330,1.346,1.358,1.373,1.387,1.408,1.428,1.451,1.470,1.493,1.516,1.538,1.572,1.599,1.620,1.648,1.680,1.710,1.746,1.775,1.808,1.846,1.879,1.918,1.982,2.015,2.055,2.106,2.159,2.205,2.253,2.313,2.360,2.435,2.495,2.552,2.645,2.706,2.793,2.860,2.913,2.929,2.923,3.013,3.135,3.267,3.363,3.503,3.648,3.756,3.899,4.037,4.277,4.281,4.271,4.298,4.336,4.351,4.350,4.348,4.362,4.365,4.353,4.384,4.429,4.442,4.440,4.483,4.494,4.480,4.471,4.472,4.475,4.483,4.482,4.490,4.490,4.500,4.499,4.497,4.508,4.508,4.518,4.525,4.533,4.540,4.554,4.561,4.575,4.591,4.591,4.599,3.941,4.622,3.817,3.464,3.412,3.521,3.649,3.502,3.473,3.287,3.209,3.297,3.378,3.240,4.787,4.799,4.816,4.835,4.861,4.878,4.892,4.915,3.123,3.008,3.008,3.099,2.935,2.729,2.686,2.705,2.730,2.747,5.166,5.193,2.663,2.637,2.603,2.000,1.921,1.883,1.865,1.873,1.865,1.829,1.853,1.856,1.954,2.055,2.480,2.437,2.527,2.516,2.497,2.527,2.562,2.579,2.500,2.486,2.518,2.563,2.541,2.505,2.498,2.490,5.141},Reflectance=[181]{41.000,41.000,43.000,46.000,43.000,46.000,48.000,44.000,45.000,45.000,46.000,46.000,49.000,48.000,43.000,41.000,47.000,42.000,45.000,49.000,48.000,50.000,48.000,51.000,45.000,49.000,51.000,53.000,55.000,53.000,55.000,53.000,54.000,57.000,55.000,58.000,57.000,58.000,59.000,56.000,58.000,55.000,56.000,57.000,60.000,61.000,59.000,61.000,55.000,54.000,58.000,61.000,58.000,59.000,60.000,59.000,62.000,59.000,58.000,56.000,49.000,48.000,43.000,50.000,55.000,55.000,55.000,54.000,54.000,50.000,54.000,51.000,48.000,49.000,67.000,72.000,71.000,74.000,74.000,74.000,75.000,76.000,76.000,76.000,74.000,75.000,74.000,73.000,73.000,77.000,76.000,75.000,76.000,77.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,76.000,75.000,69.000,70.000,75.000,75.000,75.000,96.000,76.000,102.000,87.000,80.000,99.000,107.000,106.000,103.000,101.000,78.000,103.000,113.000,19.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,112.000,75.000,78.000,113.000,76.000,80.000,75.000,73.000,72.000,51.000,73.000,71.000,64.000,74.000,75.000,84.000,87.000,79.000,73.000,73.000,73.000,71.000,72.000,68.000,84.000,90.000,70.000,70.000,76.000,76.000,75.000,71.000,71.000,71.000,69.000,69.000,61.000,63.000,67.000,32.000,24.000,19.000,29.000}
-62.066 LMS_LASER_2D_RIGHT LMS2 ID=3932,time=1225719873.707290,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=21,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.069,19.861,15.450,12.847,11.044,9.910,8.982,8.049,7.378,6.854,6.357,5.903,5.485,5.130,4.863,4.477,4.301,4.011,3.857,3.704,3.518,3.363,3.211,3.078,2.940,2.833,2.724,2.609,2.501,2.433,2.353,2.283,2.215,2.139,2.087,2.037,1.977,1.925,1.881,1.821,1.764,1.725,1.684,1.653,1.622,1.597,1.564,1.527,1.516,1.480,1.460,1.423,1.396,1.377,1.341,1.320,1.305,1.280,1.265,1.265,1.254,1.251,1.272,1.282,1.287,1.292,1.290,1.271,1.250,1.230,1.228,1.217,1.195,1.200,1.172,1.161,1.146,1.100,1.097,1.086,1.119,1.107,1.094,1.088,1.068,1.061,1.056,1.049,1.025,0.992,1.010,1.026},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,23.000,18.000,122.000,105.000,84.000,66.000,59.000,60.000,59.000,63.000,65.000,67.000,69.000,69.000,70.000,74.000,76.000,75.000,75.000,75.000,76.000,76.000,78.000,79.000,80.000,81.000,81.000,79.000,79.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,76.000,78.000,79.000,78.000,79.000,77.000,74.000,78.000,78.000,75.000,72.000,72.000,71.000,71.000,75.000,76.000,76.000,77.000,77.000,74.000,71.000,62.000,54.000,52.000,43.000,46.000,53.000,60.000,63.000,54.000,49.000,58.000,49.000,45.000,51.000,39.000,27.000,27.000,27.000,43.000,42.000,39.000,42.000,41.000,42.000,38.000,34.000,33.000,27.000,31.000,39.000}
-62.078 LMS_LASER_2D_RIGHT LMS2 ID=3933,time=1225719873.720632,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=22,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.052,-1.000,16.066,13.256,11.302,10.089,9.162,8.267,7.497,6.943,6.433,5.981,5.561,5.184,4.926,4.588,4.328,4.103,3.881,3.737,3.554,3.380,3.237,3.097,2.974,2.840,2.761,2.626,2.520,2.451,2.362,2.298,2.241,2.165,2.096,2.053,1.993,1.944,1.898,1.838,1.794,1.740,1.705,1.670,1.634,1.597,1.577,1.533,1.515,1.490,1.463,1.429,1.411,1.367,1.339,1.324,1.306,1.295,1.259,1.262,1.253,1.257,1.267,1.288,1.292,1.290,1.287,1.269,1.258,1.235,1.231,1.208,1.174,1.179,1.186,1.157,1.147,1.113,1.100,1.095,1.119,1.108,1.097,1.088,1.075,1.065,1.061,1.052,1.033,1.011,1.022,1.008},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,26.000,0.000,112.000,110.000,88.000,69.000,59.000,57.000,58.000,62.000,66.000,67.000,68.000,69.000,69.000,72.000,75.000,75.000,75.000,75.000,76.000,76.000,78.000,80.000,80.000,81.000,80.000,80.000,79.000,80.000,80.000,79.000,78.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,75.000,69.000,78.000,78.000,76.000,69.000,67.000,68.000,69.000,73.000,74.000,75.000,76.000,77.000,73.000,65.000,60.000,49.000,47.000,46.000,48.000,60.000,60.000,61.000,59.000,61.000,70.000,59.000,47.000,49.000,40.000,29.000,27.000,28.000,44.000,46.000,45.000,42.000,41.000,41.000,42.000,37.000,33.000,30.000,32.000,32.000}
-62.095 DESIRED_THRUST iJoystick 85.5708487197
-62.095 DESIRED_RUDDER iJoystick 1.02847376934
-62.107 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.4274,18.7447,-0.8107},Vel=[3x1]{-0.8012,-0.7616,7.3077},Raw=[2x1]{20.2849,-0.8107},time=1225719873.75432157516479,Speed=1.10539995911334,Pitch=0.00448670746768,Roll=0.03589365974142,PitchDot=0.01570347613687,RollDot=-0.00123384455361
-62.107 ODOMETRY_POSE iPlatform Pose=[3x1]{4.4274,18.7447,-0.8103},Vel=[3x1]{-0.8012,-0.7616,1.0246},Raw=[2x1]{20.2849,-0.8107},time=1225719873.7543,Speed=1.1054,Pitch=-0.0229,Roll=0.0280,PitchDot=0.0071,RollDot=-0.0141
-62.119 DESIRED_THRUST iJoystick 85.5708487197
-62.119 DESIRED_RUDDER iJoystick 1.02847376934
-61.244 CAMERA_FILE_WRITE iCameraLadybug time=1225719872.892,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719872.892-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719872.892-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719872.892-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719872.892-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719872.892-4.jpg
-62.090 LMS_LASER_2D_LEFT LMS1 ID=4061,time=1225719873.728451,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=58,Range=[181]{1.041,1.042,1.050,1.056,1.072,1.081,1.094,1.093,1.099,1.115,1.134,1.135,1.158,1.157,1.177,1.189,1.213,1.221,1.230,1.247,1.262,1.274,1.286,1.308,1.322,1.337,1.358,1.373,1.391,1.403,1.427,1.441,1.470,1.496,1.519,1.541,1.566,1.593,1.616,1.642,1.671,1.699,1.736,1.772,1.793,1.837,1.872,1.919,1.965,2.016,2.057,2.096,2.144,2.199,2.246,2.300,2.365,2.422,2.490,2.549,2.631,2.688,2.775,2.860,2.915,2.912,2.917,2.988,3.108,3.237,3.326,3.472,3.628,3.746,3.826,4.017,4.276,4.273,4.272,4.291,4.326,4.341,4.348,4.344,4.353,4.355,4.344,4.375,4.420,4.439,4.434,4.463,4.492,4.477,4.463,4.473,4.473,4.472,4.480,4.479,4.489,4.490,4.499,4.499,4.499,4.508,4.508,4.518,4.527,4.533,4.548,4.552,4.567,4.578,4.582,4.592,4.601,4.612,3.753,3.567,3.447,3.387,3.534,3.459,3.320,3.216,3.181,3.199,3.211,3.335,3.233,3.191,4.807,4.825,4.842,4.867,4.882,2.999,3.070,2.996,3.084,3.037,2.910,2.853,2.725,2.725,2.745,2.931,2.873,2.863,2.720,2.699,2.738,2.637,2.622,2.170,1.934,1.883,1.970,1.889,1.834,1.937,1.904,1.938,2.490,2.509,2.532,2.522,2.505,2.519,2.518,2.554,2.552,2.486,2.525,2.619,2.517,2.487,2.502,2.496,2.490},Reflectance=[181]{43.000,43.000,43.000,45.000,45.000,45.000,48.000,48.000,47.000,46.000,43.000,48.000,47.000,50.000,48.000,46.000,44.000,44.000,49.000,49.000,48.000,49.000,50.000,49.000,47.000,53.000,51.000,53.000,53.000,55.000,55.000,57.000,54.000,54.000,57.000,55.000,58.000,59.000,58.000,58.000,58.000,59.000,56.000,59.000,63.000,61.000,60.000,57.000,59.000,55.000,58.000,61.000,59.000,56.000,61.000,57.000,59.000,61.000,60.000,55.000,54.000,55.000,47.000,47.000,56.000,55.000,57.000,55.000,58.000,52.000,53.000,50.000,47.000,51.000,60.000,74.000,70.000,75.000,74.000,72.000,74.000,76.000,76.000,75.000,74.000,75.000,75.000,73.000,73.000,76.000,77.000,75.000,75.000,76.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,76.000,72.000,71.000,74.000,75.000,75.000,76.000,76.000,102.000,107.000,90.000,73.000,101.000,107.000,76.000,79.000,75.000,74.000,76.000,105.000,24.000,21.000,78.000,78.000,78.000,77.000,77.000,29.000,94.000,76.000,98.000,119.000,76.000,77.000,73.000,73.000,74.000,35.000,34.000,44.000,72.000,76.000,77.000,72.000,70.000,79.000,71.000,64.000,79.000,83.000,68.000,76.000,74.000,77.000,60.000,65.000,75.000,75.000,75.000,74.000,66.000,65.000,60.000,67.000,68.000,69.000,69.000,59.000,46.000,30.000,32.000}
-62.090 LMS_LASER_2D_RIGHT LMS2 ID=3934,time=1225719873.733973,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=23,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.272,-1.000,16.497,13.556,11.594,10.169,9.291,8.423,7.592,7.015,6.521,6.061,5.630,5.246,4.972,4.630,4.351,4.135,3.940,3.770,3.583,3.418,3.253,3.116,2.991,2.864,2.769,2.653,2.550,2.468,2.380,2.305,2.241,2.176,2.113,2.062,2.002,1.961,1.898,1.847,1.804,1.762,1.725,1.677,1.643,1.614,1.584,1.537,1.522,1.482,1.466,1.423,1.420,1.382,1.366,1.333,1.306,1.297,1.271,1.262,1.255,1.258,1.268,1.291,1.299,1.298,1.289,1.261,1.243,1.237,1.233,1.205,1.167,1.178,1.182,1.161,1.151,1.127,1.103,1.099,1.124,1.112,1.100,1.085,1.071,1.074,1.064,1.061,1.049,1.020,1.008,1.008},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,0.000,96.000,114.000,87.000,72.000,58.000,57.000,56.000,61.000,65.000,66.000,68.000,69.000,69.000,72.000,74.000,74.000,75.000,75.000,76.000,76.000,78.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,80.000,79.000,78.000,79.000,78.000,78.000,74.000,78.000,78.000,77.000,73.000,68.000,65.000,68.000,72.000,74.000,73.000,74.000,77.000,74.000,67.000,56.000,47.000,46.000,46.000,50.000,61.000,61.000,62.000,60.000,65.000,72.000,64.000,53.000,48.000,41.000,30.000,26.000,25.000,36.000,45.000,43.000,41.000,45.000,43.000,38.000,42.000,38.000,31.000,31.000,32.000}
-62.103 LMS_LASER_2D_LEFT LMS1 ID=4062,time=1225719873.741796,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=59,Range=[181]{1.043,1.048,1.056,1.065,1.071,1.071,1.080,1.087,1.099,1.114,1.128,1.135,1.160,1.171,1.171,1.191,1.199,1.223,1.224,1.239,1.252,1.274,1.281,1.307,1.320,1.337,1.345,1.378,1.390,1.413,1.425,1.443,1.465,1.488,1.516,1.539,1.567,1.587,1.617,1.639,1.663,1.699,1.733,1.764,1.800,1.829,1.864,1.910,1.966,2.011,2.051,2.090,2.144,2.187,2.236,2.287,2.348,2.420,2.471,2.554,2.629,2.655,2.765,2.855,2.912,2.912,2.913,2.959,3.095,3.206,3.319,3.468,3.626,3.733,3.772,3.991,4.293,4.263,4.259,4.269,4.313,4.340,4.340,4.338,4.343,4.356,4.346,4.358,4.398,4.431,4.424,4.453,4.486,4.476,4.462,4.473,4.472,4.472,4.479,4.481,4.482,4.488,4.498,4.497,4.499,4.499,4.506,4.508,4.519,4.525,4.534,4.543,4.551,4.551,4.573,4.585,4.599,4.602,3.549,4.630,3.604,3.555,3.659,3.541,3.379,3.288,3.216,3.203,3.203,3.247,3.349,3.355,4.804,4.820,4.835,4.854,4.877,3.003,3.003,2.930,2.995,2.889,2.889,2.853,2.791,2.790,2.809,2.951,3.189,2.757,2.717,2.676,2.581,2.275,2.126,2.077,2.155,2.300,2.552,1.900,1.841,1.982,1.946,1.961,2.499,2.522,2.512,2.505,2.477,2.510,2.529,2.533,2.526,2.529,2.535,2.528,2.545,2.508,2.481,6.463,2.506},Reflectance=[181]{39.000,41.000,45.000,41.000,46.000,46.000,46.000,49.000,47.000,46.000,44.000,48.000,43.000,44.000,49.000,46.000,46.000,41.000,50.000,49.000,47.000,44.000,48.000,51.000,54.000,49.000,53.000,51.000,53.000,52.000,54.000,54.000,59.000,58.000,56.000,58.000,55.000,56.000,54.000,60.000,59.000,59.000,58.000,56.000,56.000,57.000,60.000,58.000,56.000,56.000,59.000,58.000,59.000,59.000,57.000,59.000,60.000,60.000,55.000,49.000,53.000,57.000,45.000,41.000,55.000,55.000,59.000,57.000,59.000,58.000,53.000,48.000,46.000,57.000,59.000,74.000,73.000,74.000,76.000,71.000,70.000,73.000,76.000,75.000,74.000,75.000,75.000,73.000,72.000,76.000,77.000,75.000,76.000,76.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,75.000,72.000,72.000,75.000,76.000,75.000,76.000,6.000,76.000,108.000,104.000,106.000,107.000,86.000,79.000,79.000,76.000,76.000,86.000,109.000,108.000,77.000,78.000,78.000,78.000,78.000,37.000,96.000,77.000,97.000,78.000,77.000,77.000,74.000,74.000,69.000,62.000,101.000,77.000,76.000,77.000,69.000,80.000,74.000,70.000,77.000,69.000,73.000,84.000,67.000,77.000,79.000,81.000,69.000,75.000,77.000,75.000,74.000,76.000,75.000,73.000,69.000,74.000,71.000,35.000,76.000,43.000,29.000,63.000,39.000}
-62.103 LMS_LASER_2D_RIGHT LMS2 ID=3935,time=1225719873.747313,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=24,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.344,-1.000,16.810,13.901,11.837,10.292,9.395,8.572,7.704,7.091,6.589,6.098,5.681,5.300,4.998,4.690,4.397,4.203,3.966,3.813,3.627,3.448,3.285,3.139,3.018,2.873,2.787,2.671,2.559,2.469,2.409,2.310,2.239,2.186,2.114,2.062,2.010,1.976,1.910,1.850,1.804,1.770,1.732,1.679,1.653,1.606,1.590,1.544,1.523,1.492,1.464,1.439,1.413,1.394,1.368,1.342,1.325,1.297,1.279,1.267,1.253,1.252,1.257,1.273,1.282,1.295,1.288,1.268,1.250,1.241,1.228,1.226,1.173,1.166,1.185,1.164,1.160,1.140,1.103,1.099,1.107,1.111,1.105,1.092,1.084,1.071,1.066,1.051,1.034,1.016,1.014,1.026},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,11.000,0.000,91.000,115.000,88.000,75.000,60.000,56.000,58.000,58.000,65.000,67.000,67.000,69.000,69.000,73.000,74.000,73.000,74.000,75.000,76.000,77.000,77.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,78.000,75.000,78.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,77.000,72.000,78.000,79.000,78.000,76.000,76.000,69.000,72.000,73.000,74.000,74.000,72.000,75.000,73.000,72.000,65.000,51.000,50.000,44.000,49.000,60.000,67.000,68.000,62.000,61.000,69.000,70.000,50.000,45.000,43.000,35.000,26.000,25.000,30.000,41.000,42.000,43.000,43.000,42.000,38.000,36.000,32.000,29.000,31.000,35.000}
-62.117 LMS_LASER_2D_LEFT LMS1 ID=4063,time=1225719873.755142,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=60,Range=[181]{1.038,1.039,1.047,1.051,1.062,1.076,1.091,1.087,1.098,1.107,1.132,1.134,1.142,1.166,1.173,1.179,1.190,1.206,1.230,1.245,1.255,1.267,1.285,1.308,1.318,1.331,1.346,1.364,1.382,1.409,1.424,1.452,1.465,1.482,1.509,1.542,1.574,1.589,1.609,1.634,1.664,1.694,1.728,1.763,1.789,1.828,1.870,1.906,1.955,2.001,2.040,2.089,2.135,2.186,2.235,2.290,2.340,2.411,2.477,2.560,2.606,2.661,2.715,2.850,2.908,2.921,2.907,2.951,3.087,3.207,3.301,3.453,3.623,3.724,3.735,3.854,4.234,4.246,4.249,4.260,4.293,4.323,4.326,4.326,4.332,4.344,4.327,4.346,4.383,4.420,4.425,4.427,4.487,4.470,4.462,4.463,4.471,4.467,4.479,4.481,4.480,4.468,4.484,4.486,4.499,4.497,4.506,4.508,4.508,4.519,4.526,4.543,4.540,4.552,4.566,4.568,4.585,4.594,4.602,4.611,4.630,4.641,3.614,3.419,3.338,3.323,3.327,3.259,3.181,3.164,3.210,3.238,3.198,4.817,4.836,4.846,4.871,2.868,2.924,2.852,2.821,2.812,2.838,2.850,2.795,2.764,2.841,2.974,2.834,2.686,2.689,2.630,2.570,2.586,2.285,2.383,2.694,2.761,2.740,1.931,1.875,1.906,2.043,2.110,2.489,2.511,2.508,2.491,2.459,2.477,2.519,2.505,2.502,2.508,2.535,2.492,2.501,2.492,2.481,6.507,2.493},Reflectance=[181]{41.000,46.000,46.000,48.000,46.000,48.000,42.000,49.000,50.000,46.000,45.000,47.000,47.000,45.000,50.000,52.000,50.000,49.000,44.000,43.000,44.000,50.000,50.000,49.000,53.000,51.000,53.000,53.000,53.000,54.000,53.000,54.000,56.000,56.000,56.000,55.000,54.000,57.000,55.000,58.000,59.000,60.000,56.000,60.000,55.000,57.000,59.000,59.000,54.000,56.000,58.000,57.000,58.000,58.000,56.000,56.000,60.000,60.000,54.000,48.000,51.000,60.000,56.000,46.000,53.000,55.000,56.000,61.000,56.000,54.000,50.000,46.000,48.000,53.000,58.000,66.000,73.000,75.000,75.000,71.000,70.000,71.000,74.000,74.000,74.000,75.000,75.000,72.000,73.000,76.000,77.000,75.000,76.000,77.000,77.000,77.000,78.000,79.000,77.000,77.000,77.000,76.000,76.000,76.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,74.000,75.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,108.000,80.000,74.000,72.000,84.000,76.000,77.000,77.000,88.000,85.000,28.000,78.000,78.000,79.000,79.000,32.000,90.000,74.000,73.000,75.000,75.000,74.000,70.000,72.000,76.000,80.000,101.000,75.000,76.000,78.000,73.000,73.000,78.000,82.000,70.000,68.000,70.000,77.000,65.000,70.000,87.000,84.000,75.000,77.000,76.000,73.000,74.000,75.000,76.000,75.000,74.000,74.000,74.000,64.000,79.000,65.000,33.000,63.000,28.000}
-62.117 LMS_LASER_2D_LEFT LMS1 ID=4064,time=1225719873.768476,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=61,Range=[181]{1.033,1.050,1.054,1.065,1.063,1.072,1.086,1.089,1.099,1.118,1.128,1.131,1.148,1.160,1.178,1.187,1.194,1.218,1.223,1.242,1.260,1.266,1.283,1.298,1.322,1.337,1.352,1.371,1.392,1.409,1.418,1.442,1.464,1.479,1.505,1.529,1.565,1.590,1.604,1.633,1.659,1.691,1.722,1.761,1.790,1.820,1.866,1.901,1.951,2.004,2.037,2.089,2.132,2.176,2.223,2.290,2.342,2.399,2.483,2.552,2.602,2.688,2.728,2.839,2.896,2.921,2.906,2.936,3.099,3.208,3.306,3.441,3.610,3.723,3.741,3.828,4.153,4.246,4.241,4.257,4.294,4.318,4.329,4.327,4.325,4.339,4.329,4.339,4.376,4.410,4.415,4.427,4.468,4.455,4.445,4.452,4.461,4.457,4.461,4.470,4.471,4.476,4.477,4.484,4.488,4.487,4.491,4.492,4.503,4.509,4.519,4.524,4.538,4.546,4.562,4.579,4.577,4.586,4.594,4.613,4.625,4.636,3.587,3.395,3.324,3.329,3.394,3.276,3.154,3.145,3.142,3.191,3.319,3.266,4.816,4.836,4.854,2.893,2.963,2.838,2.791,2.671,2.630,2.700,2.786,2.784,2.930,2.931,2.751,2.698,2.707,2.672,2.603,2.595,2.653,2.647,2.663,2.058,1.976,1.916,1.906,1.912,1.995,2.117,2.482,2.498,2.519,2.510,2.466,2.476,2.499,2.498,2.493,2.495,2.486,2.459,2.541,2.528,2.525,2.507,2.530},Reflectance=[181]{43.000,38.000,41.000,42.000,40.000,41.000,44.000,46.000,47.000,43.000,44.000,46.000,46.000,43.000,48.000,49.000,48.000,42.000,46.000,46.000,47.000,49.000,49.000,48.000,47.000,50.000,52.000,52.000,54.000,54.000,54.000,53.000,56.000,54.000,54.000,53.000,54.000,57.000,56.000,57.000,57.000,59.000,56.000,55.000,59.000,57.000,57.000,62.000,56.000,57.000,57.000,57.000,57.000,58.000,55.000,56.000,57.000,58.000,49.000,48.000,54.000,51.000,54.000,49.000,55.000,51.000,56.000,58.000,54.000,47.000,48.000,49.000,43.000,49.000,57.000,64.000,70.000,75.000,75.000,72.000,71.000,72.000,75.000,75.000,74.000,73.000,75.000,73.000,73.000,75.000,77.000,75.000,76.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,76.000,77.000,76.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,75.000,75.000,77.000,76.000,76.000,76.000,76.000,77.000,78.000,109.000,83.000,75.000,74.000,90.000,92.000,77.000,77.000,76.000,80.000,106.000,5.000,78.000,78.000,78.000,32.000,99.000,75.000,74.000,79.000,77.000,77.000,75.000,72.000,89.000,77.000,81.000,76.000,79.000,76.000,72.000,68.000,71.000,75.000,65.000,1.000,75.000,68.000,70.000,75.000,83.000,86.000,76.000,76.000,74.000,74.000,74.000,74.000,69.000,71.000,74.000,75.000,75.000,72.000,80.000,77.000,36.000,31.000,30.000}
-62.133 LMS1_STATUS LMS1 AppErrorFlag=false,Uptime=-1619.63,MOOSName=LMS1,Publishing=LMS1_STATUS,LMS_LASER_2D_LEFT,MOOS_DEBUG,Subscribing=LASER_LAG,LMS1_CMD,LOCAL_LASER_LAG,
-62.143 DESIRED_THRUST iJoystick 85.5708487197
-62.143 DESIRED_RUDDER iJoystick 1.02847376934
-62.117 LMS_LASER_2D_RIGHT LMS2 ID=3936,time=1225719873.760654,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=25,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.550,17.201,14.123,12.058,10.433,9.477,8.683,7.786,7.155,6.651,6.173,5.749,5.372,5.016,4.717,4.491,4.221,3.992,3.836,3.627,3.468,3.309,3.171,3.037,2.891,2.806,2.676,2.569,2.477,2.405,2.339,2.257,2.193,2.130,2.061,2.010,1.966,1.908,1.866,1.829,1.775,1.732,1.680,1.654,1.616,1.580,1.556,1.521,1.497,1.472,1.445,1.415,1.393,1.384,1.351,1.328,1.305,1.279,1.266,1.262,1.255,1.253,1.265,1.268,1.294,1.295,1.286,1.250,1.257,1.249,1.229,1.217,1.180,1.180,1.168,1.157,1.147,1.103,1.102,1.083,1.113,1.108,1.094,1.079,1.070,1.022,1.018,1.012,1.000,1.029,1.020},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,20.000,76.000,116.000,88.000,78.000,62.000,54.000,59.000,60.000,64.000,66.000,67.000,68.000,70.000,72.000,72.000,72.000,74.000,74.000,76.000,77.000,76.000,80.000,80.000,81.000,81.000,79.000,80.000,80.000,77.000,78.000,78.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,77.000,77.000,78.000,78.000,78.000,77.000,76.000,75.000,73.000,75.000,71.000,72.000,75.000,73.000,74.000,72.000,63.000,56.000,44.000,44.000,56.000,68.000,59.000,51.000,58.000,61.000,66.000,56.000,43.000,40.000,37.000,26.000,25.000,27.000,40.000,43.000,44.000,45.000,37.000,26.000,25.000,25.000,26.000,34.000,34.000}
-62.130 LMS_LASER_2D_LEFT LMS1 ID=4065,time=1225719873.781808,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=62,Range=[181]{1.025,1.043,1.051,1.060,1.062,1.075,1.090,1.092,1.100,1.105,1.124,1.139,1.142,1.158,1.172,1.184,1.191,1.208,1.225,1.242,1.250,1.267,1.281,1.299,1.317,1.339,1.347,1.372,1.394,1.408,1.425,1.443,1.463,1.482,1.504,1.538,1.560,1.584,1.606,1.626,1.663,1.689,1.722,1.751,1.777,1.821,1.857,1.904,1.944,1.998,2.040,2.075,2.123,2.173,2.220,2.283,2.337,2.400,2.472,2.548,2.609,2.683,2.755,2.825,2.894,2.915,2.903,2.931,3.110,3.208,3.306,3.422,3.600,3.712,3.749,3.837,4.141,4.237,4.237,4.246,4.284,4.318,4.329,4.327,4.326,4.341,4.320,4.331,4.374,4.407,4.406,4.411,4.458,4.446,4.444,4.453,4.454,4.447,4.453,4.463,4.460,4.469,4.471,4.479,4.487,4.487,4.485,4.492,4.491,4.509,4.510,4.518,4.523,4.538,4.554,4.567,4.567,4.585,4.591,4.609,4.622,4.633,4.641,3.384,3.268,3.307,3.433,3.353,3.232,3.146,3.130,3.143,3.273,4.795,4.820,4.828,4.853,2.987,3.028,2.863,2.800,2.611,2.573,2.622,2.731,2.798,3.012,2.941,2.916,2.823,2.817,2.637,2.606,2.698,2.623,2.601,2.187,1.990,1.913,1.931,2.001,2.037,2.027,2.114,2.498,2.500,2.497,2.457,2.469,2.456,2.486,2.566,2.506,2.480,2.468,2.462,2.466,2.543,2.550,2.475,2.299},Reflectance=[181]{43.000,39.000,43.000,44.000,46.000,47.000,46.000,47.000,51.000,46.000,46.000,45.000,47.000,47.000,46.000,51.000,50.000,46.000,45.000,45.000,46.000,50.000,52.000,52.000,49.000,50.000,50.000,49.000,51.000,53.000,54.000,54.000,55.000,56.000,54.000,54.000,56.000,59.000,57.000,58.000,59.000,58.000,58.000,58.000,58.000,57.000,57.000,55.000,57.000,58.000,54.000,59.000,61.000,60.000,58.000,58.000,55.000,59.000,52.000,46.000,49.000,49.000,50.000,50.000,54.000,52.000,58.000,59.000,51.000,50.000,48.000,48.000,45.000,48.000,53.000,62.000,69.000,74.000,74.000,72.000,70.000,72.000,75.000,75.000,74.000,74.000,75.000,73.000,73.000,75.000,77.000,76.000,76.000,78.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,76.000,77.000,77.000,76.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,76.000,75.000,76.000,76.000,76.000,75.000,75.000,76.000,77.000,77.000,102.000,75.000,75.000,99.000,113.000,100.000,77.000,75.000,76.000,105.000,77.000,78.000,78.000,78.000,23.000,102.000,77.000,75.000,79.000,74.000,75.000,75.000,62.000,111.000,80.000,81.000,106.000,109.000,74.000,68.000,60.000,73.000,69.000,77.000,72.000,70.000,72.000,79.000,87.000,85.000,87.000,76.000,74.000,68.000,69.000,72.000,73.000,67.000,45.000,56.000,70.000,74.000,72.000,76.000,79.000,10.000,76.000,41.000}
-62.130 LMS_LASER_2D_RIGHT LMS2 ID=3937,time=1225719873.773995,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=26,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.403,14.297,12.225,10.555,9.557,8.733,7.831,7.221,6.678,6.200,5.759,5.380,5.076,4.725,4.519,4.239,4.002,3.844,3.651,3.474,3.311,3.194,3.054,2.916,2.807,2.667,2.569,2.495,2.421,2.361,2.275,2.200,2.131,2.071,2.027,1.967,1.910,1.875,1.830,1.784,1.745,1.695,1.662,1.624,1.580,1.560,1.533,1.498,1.463,1.438,1.420,1.401,1.389,1.360,1.333,1.315,1.286,1.280,1.266,1.248,1.253,1.250,1.272,1.282,1.277,1.270,1.251,1.257,1.260,1.233,1.212,1.208,1.194,1.178,1.159,1.152,1.103,1.114,1.093,1.074,1.096,1.095,1.078,1.063,1.025,1.026,1.015,1.006,1.005,1.028},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,71.000,119.000,91.000,79.000,64.000,56.000,60.000,58.000,63.000,67.000,67.000,69.000,70.000,73.000,72.000,73.000,75.000,74.000,76.000,76.000,74.000,79.000,80.000,80.000,81.000,79.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,79.000,78.000,78.000,79.000,79.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,74.000,73.000,73.000,76.000,73.000,75.000,77.000,76.000,68.000,54.000,50.000,52.000,61.000,69.000,59.000,49.000,56.000,58.000,53.000,50.000,43.000,43.000,44.000,27.000,25.000,25.000,27.000,34.000,42.000,40.000,34.000,26.000,25.000,24.000,25.000,29.000,37.000}
-62.130 LMS_LASER_2D_RIGHT LMS2 ID=3938,time=1225719873.787322,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=27,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.718,18.200,14.680,12.451,10.810,9.630,8.771,7.911,7.248,6.741,6.262,5.822,5.416,5.112,4.750,4.544,4.292,4.039,3.843,3.658,3.512,3.321,3.207,3.059,2.930,2.774,2.667,2.577,2.504,2.442,2.362,2.293,2.209,2.140,2.079,2.028,1.961,1.927,1.875,1.829,1.791,1.745,1.706,1.662,1.625,1.592,1.569,1.534,1.497,1.462,1.444,1.422,1.398,1.377,1.360,1.333,1.315,1.299,1.280,1.266,1.261,1.247,1.249,1.269,1.265,1.243,1.250,1.249,1.247,1.249,1.233,1.216,1.212,1.201,1.177,1.156,1.159,1.103,1.105,1.094,1.079,1.064,1.092,1.079,1.078,1.039,1.023,1.007,1.001,0.998,1.013},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,1.000,45.000,122.000,97.000,78.000,65.000,57.000,58.000,58.000,63.000,66.000,68.000,70.000,69.000,73.000,72.000,72.000,75.000,74.000,75.000,77.000,74.000,77.000,79.000,79.000,82.000,79.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,79.000,79.000,79.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,77.000,76.000,76.000,72.000,73.000,74.000,74.000,75.000,76.000,75.000,67.000,60.000,64.000,71.000,76.000,75.000,64.000,55.000,56.000,60.000,54.000,46.000,41.000,42.000,43.000,27.000,25.000,24.000,24.000,27.000,41.000,45.000,42.000,29.000,25.000,24.000,24.000,25.000,32.000}
-62.143 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.4513,18.7674,-0.8132},Vel=[3x1]{-0.7967,-0.7536,-1.0256},Raw=[2x1]{20.3179,-0.8132},time=1225719873.79041838645935,Speed=1.09663853275313,Pitch=0.00448670746768,Roll=0.03365030600758,PitchDot=0.03140695227374,RollDot=-0.00008973414935
-62.143 ODOMETRY_POSE iPlatform Pose=[3x1]{4.4513,18.7674,-0.8128},Vel=[3x1]{-0.7967,-0.7536,-1.0258},Raw=[2x1]{20.3179,-0.8132},time=1225719873.7904,Speed=1.0966,Pitch=-0.0214,Roll=0.0264,PitchDot=0.0164,RollDot=0.0268
-62.143 LMS_LASER_2D_LEFT LMS1 ID=4066,time=1225719873.795141,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=63,Range=[181]{1.041,1.046,1.049,1.058,1.067,1.073,1.081,1.090,1.109,1.115,1.120,1.132,1.143,1.162,1.173,1.179,1.194,1.211,1.229,1.233,1.246,1.267,1.286,1.298,1.315,1.338,1.354,1.362,1.387,1.400,1.422,1.434,1.460,1.480,1.504,1.529,1.563,1.583,1.604,1.633,1.663,1.690,1.718,1.750,1.780,1.816,1.862,1.896,1.953,1.993,2.035,2.078,2.123,2.166,2.217,2.277,2.339,2.394,2.460,2.544,2.612,2.674,2.755,2.830,2.896,2.912,2.892,2.923,3.110,3.199,3.301,3.412,3.584,3.701,3.754,3.851,4.126,4.245,4.237,4.235,4.274,4.309,4.318,4.321,4.320,4.335,4.320,4.326,4.372,4.400,4.406,4.410,4.457,4.444,4.443,4.445,4.445,4.445,4.445,4.454,4.456,4.462,4.464,4.461,4.472,4.480,4.484,4.491,4.490,4.500,4.509,4.515,4.524,4.529,4.545,4.558,4.567,4.576,4.593,4.600,4.610,4.625,4.635,3.395,3.268,3.289,3.407,4.702,3.300,3.228,3.120,3.144,3.265,4.788,4.808,4.834,3.119,4.868,3.047,2.662,2.612,2.596,2.573,2.601,2.666,2.824,2.973,3.027,2.896,2.867,2.768,2.664,2.668,2.692,2.599,2.376,2.096,1.999,1.993,2.006,2.467,2.167,1.967,2.111,2.510,2.492,2.491,2.483,2.476,2.418,2.423,2.495,2.520,2.539,2.510,2.448,2.448,2.430,2.498,2.281,2.208},Reflectance=[181]{38.000,38.000,42.000,43.000,43.000,46.000,45.000,45.000,43.000,45.000,49.000,45.000,43.000,44.000,45.000,49.000,48.000,48.000,44.000,46.000,48.000,45.000,46.000,51.000,48.000,54.000,53.000,52.000,51.000,53.000,52.000,54.000,54.000,55.000,54.000,53.000,57.000,58.000,56.000,57.000,55.000,55.000,59.000,58.000,59.000,55.000,55.000,59.000,57.000,60.000,56.000,56.000,61.000,61.000,61.000,59.000,59.000,60.000,54.000,44.000,46.000,50.000,54.000,49.000,51.000,51.000,62.000,60.000,47.000,54.000,49.000,51.000,47.000,47.000,48.000,59.000,67.000,74.000,74.000,71.000,70.000,72.000,75.000,75.000,75.000,75.000,75.000,74.000,72.000,75.000,77.000,75.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,76.000,75.000,76.000,76.000,76.000,76.000,75.000,76.000,77.000,78.000,113.000,75.000,75.000,99.000,77.000,114.000,96.000,75.000,74.000,106.000,77.000,78.000,78.000,20.000,75.000,112.000,86.000,78.000,78.000,74.000,75.000,70.000,32.000,36.000,109.000,79.000,107.000,70.000,74.000,70.000,72.000,74.000,70.000,78.000,74.000,81.000,82.000,67.000,80.000,78.000,86.000,74.000,71.000,56.000,71.000,74.000,70.000,74.000,58.000,46.000,58.000,50.000,76.000,76.000,71.000,76.000,79.000,68.000}
-62.167 DESIRED_THRUST iJoystick 85.5708487197
-62.167 DESIRED_RUDDER iJoystick 0
-62.123 ICAMERABUMBLEBEE_STATUS iCameraBumbleBee AppErrorFlag=false,Uptime=-1547.12,MOOSName=iCameraBumbleBee,Publishing=ICAMERABUMBLEBEE_STATUS,Subscribing=CAMERA_COMMAND,LOGGER_DIRECTORY,MARGE_ODOMETRY,NAV_POSE,SET_INTERPOSE_COMMAND,
-62.154 LMS_LASER_2D_LEFT LMS1 ID=4067,time=1225719873.808470,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=64,Range=[181]{1.037,1.039,1.050,1.051,1.064,1.070,1.080,1.091,1.103,1.114,1.123,1.136,1.154,1.161,1.164,1.179,1.199,1.205,1.229,1.237,1.253,1.262,1.281,1.299,1.317,1.337,1.358,1.368,1.383,1.401,1.421,1.443,1.459,1.477,1.499,1.523,1.555,1.576,1.605,1.625,1.657,1.688,1.722,1.745,1.779,1.820,1.852,1.897,1.943,1.988,2.025,2.081,2.123,2.175,2.218,2.271,2.332,2.400,2.451,2.545,2.603,2.679,2.744,2.826,2.889,2.908,2.894,2.918,3.094,3.199,3.298,3.416,3.568,3.700,3.768,3.854,4.097,4.238,4.236,4.237,4.275,4.311,4.321,4.313,4.308,4.329,4.318,4.327,4.361,4.396,4.405,4.409,4.455,4.442,4.436,4.438,4.446,4.439,4.446,4.454,4.457,4.453,4.463,4.463,4.473,4.471,4.474,4.491,4.489,4.498,4.509,4.515,4.524,4.531,4.545,4.556,4.568,4.576,4.586,4.602,4.613,4.623,4.635,3.266,3.326,3.280,3.416,4.700,4.717,3.306,3.184,3.126,3.260,3.102,4.808,4.825,3.098,3.082,2.804,2.531,2.536,2.581,2.574,2.600,2.640,5.034,5.055,3.055,2.916,2.762,2.739,2.710,2.783,2.700,2.691,2.781,2.744,2.572,2.567,2.553,2.499,1.936,1.883,2.152,2.496,2.475,2.520,2.496,2.507,2.492,2.378,2.409,2.432,2.466,2.509,2.503,2.433,2.404,2.379,2.235,2.251},Reflectance=[181]{40.000,35.000,43.000,48.000,45.000,44.000,45.000,42.000,44.000,45.000,45.000,48.000,40.000,43.000,46.000,49.000,50.000,49.000,44.000,48.000,47.000,48.000,48.000,48.000,49.000,46.000,47.000,51.000,50.000,54.000,52.000,54.000,53.000,53.000,55.000,55.000,53.000,59.000,57.000,58.000,60.000,58.000,56.000,59.000,59.000,57.000,55.000,55.000,57.000,57.000,59.000,58.000,62.000,61.000,61.000,60.000,61.000,59.000,54.000,44.000,47.000,48.000,50.000,47.000,48.000,53.000,58.000,61.000,48.000,50.000,52.000,50.000,48.000,47.000,46.000,53.000,66.000,72.000,74.000,72.000,70.000,72.000,75.000,76.000,74.000,75.000,75.000,75.000,72.000,74.000,76.000,75.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,76.000,75.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,78.000,34.000,88.000,75.000,98.000,76.000,76.000,111.000,83.000,74.000,110.000,16.000,78.000,78.000,30.000,29.000,126.000,78.000,74.000,79.000,75.000,74.000,67.000,75.000,76.000,119.000,80.000,79.000,72.000,74.000,75.000,79.000,69.000,67.000,65.000,66.000,75.000,71.000,61.000,67.000,63.000,86.000,70.000,65.000,50.000,72.000,71.000,71.000,66.000,67.000,54.000,65.000,61.000,75.000,74.000,73.000,63.000,76.000,78.000}
-62.154 LMS_LASER_2D_RIGHT LMS2 ID=3939,time=1225719873.800659,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=28,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.035,18.197,14.968,12.516,10.812,9.712,8.783,7.945,7.289,6.768,6.279,5.840,5.434,5.129,4.817,4.570,4.293,4.045,3.846,3.654,3.513,3.346,3.207,3.056,2.929,2.749,2.672,2.592,2.510,2.450,2.354,2.293,2.210,2.139,2.079,2.028,1.977,1.927,1.875,1.821,1.792,1.757,1.715,1.680,1.643,1.613,1.566,1.530,1.506,1.474,1.446,1.425,1.406,1.380,1.362,1.341,1.323,1.297,1.287,1.262,1.255,1.249,1.250,1.263,1.251,1.244,1.245,1.244,1.241,1.230,1.226,1.218,1.200,1.193,1.177,1.154,1.156,1.106,1.099,1.102,1.094,1.067,1.079,1.082,1.082,1.060,1.018,1.007,1.009,1.001,1.024},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,16.000,40.000,117.000,97.000,79.000,64.000,58.000,57.000,57.000,63.000,66.000,67.000,70.000,69.000,70.000,70.000,74.000,73.000,75.000,77.000,77.000,74.000,77.000,78.000,79.000,83.000,81.000,79.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,79.000,79.000,79.000,78.000,77.000,77.000,78.000,76.000,76.000,77.000,77.000,77.000,77.000,72.000,72.000,74.000,70.000,74.000,77.000,75.000,68.000,62.000,69.000,73.000,77.000,76.000,68.000,63.000,61.000,57.000,57.000,57.000,43.000,42.000,42.000,28.000,25.000,25.000,24.000,26.000,31.000,38.000,42.000,36.000,26.000,26.000,25.000,25.000,33.000}
-62.180 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.4834,18.7978,-0.8147},Vel=[3x1]{-0.8137,-0.7675,-1.6667},Raw=[2x1]{20.3621,-0.8147},time=1225719873.82742643356323,Speed=1.11854209865366,Pitch=0.00448670746768,Roll=0.03140695227374,PitchDot=0.03140695227374,RollDot=-0.00026920244806
-62.180 ODOMETRY_POSE iPlatform Pose=[3x1]{4.4834,18.7978,-0.8144},Vel=[3x1]{-0.8137,-0.7675,-1.6667},Raw=[2x1]{20.3621,-0.8147},time=1225719873.8274,Speed=1.1185,Pitch=-0.0198,Roll=0.0248,PitchDot=-0.0027,RollDot=0.0313
-62.191 DESIRED_THRUST iJoystick 85.5708487197
-62.191 DESIRED_RUDDER iJoystick 0
-61.807 IRELAYBOX_STATUS iRelayBox AppErrorFlag=false,Uptime=62.1291,MOOSName=iRelayBox,Publishing=IRELAYBOX_STATUS,RELAYBOX_STATUS,Subscribing=RELAYBOX_CMD,
-61.807 RELAYBOX_STATUS iRelayBox LADYBUG is OFF,LMS1 is ON,LMS2 is ON,P10 is OFF,P11 is OFF,P12 is OFF,P13 is OFF,P14 is OFF,P15 is OFF,P16 is OFF,P5 is OFF,P6 is OFF,P7 is OFF,P8 is OFF,P9 is OFF,PANTILT is ON,
-62.166 LMS_LASER_2D_LEFT LMS1 ID=4068,time=1225719873.821800,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=65,Range=[181]{1.033,1.049,1.047,1.053,1.065,1.069,1.081,1.093,1.110,1.107,1.128,1.131,1.140,1.157,1.177,1.187,1.192,1.203,1.223,1.234,1.254,1.266,1.278,1.295,1.319,1.340,1.349,1.367,1.382,1.401,1.423,1.442,1.458,1.478,1.505,1.521,1.556,1.579,1.607,1.632,1.659,1.691,1.715,1.749,1.780,1.821,1.856,1.903,1.945,1.998,2.034,2.072,2.120,2.166,2.221,2.279,2.333,2.393,2.460,2.548,2.611,2.677,2.750,2.829,2.892,2.904,2.896,2.929,3.097,3.206,3.296,3.408,3.552,3.711,3.777,3.892,4.133,4.230,4.234,4.240,4.268,4.305,4.312,4.312,4.309,4.327,4.318,4.325,4.359,4.395,4.403,4.410,4.447,4.442,4.437,4.439,4.437,4.448,4.445,4.447,4.455,4.453,4.462,4.462,4.461,4.473,4.474,4.481,4.490,4.498,4.507,4.513,4.524,4.529,4.537,4.547,4.558,4.576,4.586,4.593,4.604,4.614,4.635,3.282,3.386,3.312,3.447,3.330,4.709,3.235,3.256,3.116,3.194,3.241,3.112,4.828,3.093,3.093,2.890,2.581,2.537,2.556,2.573,2.600,2.631,5.033,5.055,2.959,2.989,2.815,2.743,2.749,2.783,2.756,2.821,2.818,2.832,2.754,2.774,2.763,2.535,1.897,1.909,2.307,2.466,2.498,2.506,2.518,2.540,2.500,2.355,2.342,2.412,2.457,2.518,2.530,2.396,2.369,2.388,2.373,2.270},Reflectance=[181]{38.000,38.000,45.000,44.000,47.000,44.000,46.000,48.000,43.000,42.000,36.000,46.000,46.000,46.000,43.000,44.000,47.000,51.000,50.000,50.000,48.000,50.000,47.000,46.000,46.000,47.000,51.000,51.000,50.000,50.000,53.000,53.000,53.000,54.000,54.000,54.000,54.000,56.000,54.000,57.000,57.000,59.000,58.000,57.000,59.000,58.000,56.000,54.000,58.000,54.000,59.000,61.000,60.000,57.000,58.000,60.000,61.000,59.000,54.000,45.000,45.000,45.000,48.000,48.000,49.000,51.000,55.000,58.000,53.000,46.000,47.000,46.000,49.000,44.000,47.000,48.000,65.000,72.000,73.000,73.000,71.000,73.000,75.000,75.000,75.000,75.000,75.000,74.000,71.000,74.000,76.000,75.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,77.000,76.000,75.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,78.000,23.000,104.000,79.000,95.000,27.000,76.000,34.000,97.000,76.000,106.000,117.000,28.000,78.000,26.000,31.000,120.000,82.000,74.000,75.000,74.000,74.000,59.000,75.000,76.000,57.000,98.000,79.000,73.000,73.000,75.000,77.000,73.000,67.000,64.000,65.000,67.000,58.000,63.000,75.000,71.000,78.000,61.000,60.000,59.000,20.000,51.000,64.000,67.000,64.000,73.000,63.000,74.000,54.000,49.000,66.000,74.000,77.000,78.000}
-62.166 LMS_LASER_2D_RIGHT LMS2 ID=3940,time=1225719873.813997,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=29,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.089,18.266,15.040,12.547,10.825,9.722,8.820,7.972,7.303,6.767,6.271,5.868,5.442,5.138,4.828,4.571,4.293,4.082,3.845,3.682,3.528,3.352,3.204,3.069,2.923,2.750,2.681,2.597,2.519,2.450,2.345,2.286,2.210,2.130,2.087,2.019,1.969,1.927,1.873,1.829,1.794,1.758,1.724,1.680,1.643,1.612,1.577,1.539,1.524,1.489,1.458,1.425,1.408,1.382,1.361,1.342,1.325,1.304,1.294,1.262,1.258,1.250,1.250,1.263,1.263,1.257,1.259,1.244,1.235,1.231,1.213,1.209,1.209,1.192,1.175,1.160,1.151,1.136,1.108,1.093,1.093,1.067,1.088,1.082,1.080,1.066,1.061,1.028,1.007,1.016,1.031},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,42.000,120.000,100.000,80.000,65.000,58.000,57.000,56.000,62.000,66.000,67.000,71.000,69.000,71.000,71.000,73.000,74.000,74.000,77.000,76.000,75.000,79.000,79.000,80.000,83.000,81.000,78.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,78.000,78.000,76.000,74.000,77.000,78.000,77.000,74.000,74.000,70.000,68.000,72.000,75.000,76.000,68.000,62.000,62.000,65.000,68.000,76.000,72.000,65.000,65.000,61.000,57.000,57.000,42.000,43.000,43.000,32.000,25.000,25.000,25.000,26.000,35.000,41.000,42.000,41.000,35.000,29.000,26.000,29.000,38.000}
-62.177 LMS_LASER_2D_RIGHT LMS2 ID=3941,time=1225719873.827331,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=30,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.108,18.287,14.997,12.539,10.824,9.731,8.825,7.947,7.295,6.758,6.280,5.868,5.460,5.137,4.828,4.588,4.321,4.084,3.852,3.672,3.520,3.342,3.210,3.064,2.923,2.779,2.666,2.596,2.531,2.451,2.355,2.286,2.210,2.145,2.097,2.027,1.977,1.928,1.873,1.830,1.797,1.759,1.716,1.668,1.634,1.599,1.566,1.540,1.516,1.474,1.456,1.433,1.406,1.380,1.360,1.336,1.322,1.304,1.294,1.279,1.263,1.253,1.244,1.257,1.269,1.258,1.252,1.240,1.223,1.209,1.206,1.206,1.201,1.186,1.172,1.156,1.154,1.150,1.100,1.093,1.075,1.084,1.098,1.087,1.078,1.070,1.061,1.016,1.002,0.996,1.031},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,8.000,44.000,120.000,101.000,80.000,64.000,56.000,58.000,56.000,62.000,67.000,66.000,70.000,68.000,71.000,71.000,72.000,74.000,74.000,76.000,77.000,75.000,78.000,81.000,80.000,80.000,79.000,80.000,80.000,80.000,81.000,81.000,80.000,79.000,81.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,79.000,78.000,79.000,77.000,75.000,78.000,78.000,79.000,78.000,77.000,77.000,77.000,76.000,75.000,71.000,70.000,68.000,71.000,74.000,73.000,72.000,66.000,56.000,67.000,76.000,78.000,75.000,72.000,67.000,66.000,61.000,54.000,45.000,42.000,45.000,38.000,27.000,25.000,25.000,29.000,40.000,44.000,44.000,39.000,37.000,28.000,26.000,27.000,38.000}
-62.190 LMS_LASER_2D_LEFT LMS1 ID=4069,time=1225719873.835140,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=66,Range=[181]{1.032,1.043,1.050,1.056,1.064,1.072,1.086,1.092,1.107,1.110,1.126,1.134,1.145,1.158,1.174,1.182,1.200,1.215,1.227,1.238,1.254,1.271,1.280,1.297,1.316,1.331,1.347,1.365,1.392,1.406,1.416,1.434,1.469,1.478,1.506,1.521,1.555,1.579,1.599,1.633,1.661,1.681,1.721,1.748,1.784,1.822,1.866,1.900,1.955,1.989,2.030,2.072,2.130,2.178,2.225,2.273,2.340,2.399,2.460,2.548,2.611,2.678,2.758,2.837,2.899,2.901,2.895,2.936,3.102,3.217,3.306,3.411,3.564,3.724,3.809,3.988,4.157,4.230,4.235,4.238,4.277,4.305,4.312,4.301,4.311,4.329,4.321,4.322,4.360,4.385,4.405,4.401,4.447,4.435,4.437,4.436,4.437,4.438,4.439,4.448,4.446,4.458,4.462,4.461,4.472,4.473,4.472,4.481,4.489,4.495,4.496,4.505,4.514,4.523,4.540,4.547,4.558,4.569,4.587,4.593,4.605,4.623,4.631,4.643,3.417,3.315,3.415,3.331,4.709,3.299,3.227,3.071,3.079,3.176,3.241,3.131,4.836,3.109,3.111,2.610,2.537,2.555,2.574,2.609,2.654,3.938,5.054,2.899,2.893,2.916,2.760,2.742,2.763,2.806,2.770,2.815,2.788,3.003,2.940,2.714,2.018,1.875,1.932,2.492,2.462,2.500,2.506,5.671,2.474,2.486,2.356,2.334,2.378,2.442,2.520,2.423,2.349,2.366,2.416,2.396,2.243},Reflectance=[181]{42.000,44.000,43.000,42.000,46.000,45.000,44.000,47.000,45.000,43.000,43.000,47.000,44.000,47.000,46.000,46.000,47.000,45.000,47.000,49.000,48.000,43.000,48.000,51.000,48.000,51.000,54.000,54.000,54.000,52.000,53.000,54.000,54.000,54.000,55.000,58.000,53.000,56.000,54.000,58.000,58.000,59.000,56.000,57.000,57.000,58.000,57.000,57.000,58.000,58.000,57.000,62.000,56.000,59.000,60.000,63.000,60.000,58.000,54.000,46.000,46.000,51.000,47.000,48.000,49.000,50.000,55.000,58.000,51.000,47.000,48.000,47.000,50.000,45.000,45.000,52.000,65.000,72.000,74.000,72.000,71.000,73.000,75.000,75.000,75.000,75.000,75.000,73.000,71.000,73.000,76.000,75.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,76.000,78.000,108.000,78.000,98.000,23.000,76.000,21.000,104.000,76.000,76.000,97.000,117.000,26.000,78.000,30.000,117.000,85.000,74.000,74.000,75.000,74.000,57.000,3.000,76.000,56.000,76.000,80.000,73.000,71.000,74.000,76.000,71.000,66.000,69.000,54.000,52.000,59.000,77.000,74.000,68.000,62.000,59.000,71.000,48.000,65.000,32.000,75.000,77.000,71.000,73.000,69.000,54.000,10.000,71.000,73.000,72.000,79.000,80.000}
-62.190 LMS_LASER_2D_RIGHT LMS2 ID=3942,time=1225719873.840666,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=31,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.829,18.006,14.794,12.464,10.775,9.658,8.797,7.934,7.244,6.732,6.226,5.832,5.442,5.129,4.817,4.571,4.313,4.057,3.878,3.674,3.534,3.334,3.202,3.041,2.903,2.809,2.645,2.589,2.533,2.453,2.359,2.292,2.209,2.145,2.095,2.037,1.986,1.927,1.872,1.822,1.780,1.752,1.707,1.679,1.629,1.605,1.570,1.535,1.515,1.465,1.464,1.436,1.404,1.379,1.357,1.342,1.327,1.308,1.287,1.271,1.255,1.253,1.246,1.243,1.269,1.268,1.271,1.238,1.234,1.223,1.199,1.207,1.201,1.178,1.169,1.156,1.155,1.146,1.100,1.094,1.075,1.092,1.093,1.074,1.075,1.069,1.044,1.028,1.028,1.020,1.032},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,47.000,121.000,99.000,78.000,64.000,56.000,57.000,56.000,63.000,67.000,67.000,70.000,69.000,71.000,71.000,73.000,74.000,74.000,77.000,78.000,76.000,78.000,79.000,79.000,79.000,75.000,81.000,81.000,81.000,79.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,80.000,79.000,79.000,77.000,78.000,71.000,76.000,78.000,78.000,78.000,78.000,76.000,77.000,75.000,73.000,63.000,62.000,69.000,73.000,74.000,73.000,77.000,71.000,60.000,56.000,61.000,74.000,70.000,67.000,70.000,69.000,61.000,58.000,51.000,49.000,45.000,37.000,27.000,27.000,25.000,31.000,43.000,46.000,43.000,37.000,31.000,29.000,30.000,31.000,38.000}
-62.215 DESIRED_THRUST iJoystick 85.5708487197
-62.215 DESIRED_RUDDER iJoystick 1.02847376934
-62.215 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.5154,18.8279,-0.8145},Vel=[3x1]{-0.7998,-0.7545,-5.5128},Raw=[2x1]{20.4060,-0.8145},time=1225719873.86251258850098,Speed=1.09955900820654,Pitch=0.00448670746768,Roll=0.03140695227374,PitchDot=-0.00000000000000,RollDot=0.00069543965749
-62.215 ODOMETRY_POSE iPlatform Pose=[3x1]{4.5154,18.8279,-0.8142},Vel=[3x1]{-0.7998,-0.7545,0.7704},Raw=[2x1]{20.4060,-0.8145},time=1225719873.8625,Speed=1.0996,Pitch=-0.0198,Roll=0.0248,PitchDot=0.0005,RollDot=0.0005
-62.202 LMS_LASER_2D_LEFT LMS1 ID=4070,time=1225719873.848477,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=67,Range=[181]{1.037,1.045,1.048,1.058,1.068,1.077,1.085,1.090,1.107,1.111,1.124,1.138,1.148,1.163,1.177,1.185,1.204,1.217,1.233,1.238,1.248,1.271,1.284,1.299,1.320,1.337,1.346,1.374,1.376,1.408,1.423,1.451,1.469,1.479,1.509,1.523,1.556,1.585,1.607,1.624,1.655,1.687,1.723,1.758,1.788,1.823,1.869,1.902,1.952,1.998,2.041,2.080,2.138,2.186,2.225,2.282,2.341,2.403,2.469,2.553,2.613,2.688,2.748,2.847,2.891,2.901,2.895,2.952,3.130,3.227,3.333,3.420,3.572,3.736,3.894,4.131,4.184,4.232,4.227,4.238,4.268,4.305,4.309,4.305,4.311,4.326,4.308,4.320,4.363,4.397,4.395,4.400,4.437,4.434,4.438,4.438,4.439,4.438,4.439,4.446,4.446,4.455,4.454,4.454,4.463,4.473,4.474,4.480,4.484,4.496,4.496,4.505,4.514,4.529,4.540,4.547,4.559,4.569,4.577,4.594,4.607,4.615,4.632,3.438,3.266,3.309,3.495,4.690,4.708,3.107,3.161,3.072,3.071,3.095,3.202,3.139,4.835,4.858,3.108,2.656,2.581,2.648,2.668,2.614,2.681,4.134,3.749,2.995,2.883,2.904,2.802,2.729,2.712,2.756,2.760,2.806,2.832,3.128,2.794,2.646,1.959,1.875,2.266,2.463,2.461,2.486,2.509,2.456,2.475,2.545,2.403,2.331,2.361,2.414,2.539,2.368,2.342,2.359,2.390,2.458,2.322},Reflectance=[181]{41.000,40.000,47.000,43.000,43.000,44.000,43.000,45.000,41.000,48.000,46.000,46.000,41.000,44.000,43.000,48.000,49.000,47.000,45.000,49.000,49.000,48.000,49.000,52.000,50.000,53.000,53.000,54.000,55.000,53.000,53.000,53.000,54.000,54.000,56.000,55.000,54.000,55.000,58.000,57.000,59.000,57.000,57.000,58.000,59.000,58.000,58.000,58.000,57.000,54.000,55.000,61.000,56.000,58.000,60.000,63.000,61.000,60.000,55.000,44.000,45.000,55.000,55.000,49.000,49.000,50.000,55.000,58.000,48.000,48.000,48.000,47.000,50.000,47.000,49.000,56.000,67.000,73.000,74.000,72.000,71.000,73.000,75.000,76.000,75.000,74.000,74.000,72.000,72.000,74.000,76.000,75.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,76.000,76.000,76.000,76.000,76.000,78.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,112.000,76.000,79.000,109.000,76.000,76.000,22.000,99.000,76.000,76.000,75.000,106.000,36.000,78.000,77.000,122.000,87.000,81.000,105.000,106.000,70.000,56.000,102.000,16.000,121.000,76.000,77.000,75.000,72.000,70.000,75.000,73.000,66.000,66.000,55.000,40.000,65.000,78.000,66.000,50.000,56.000,70.000,75.000,53.000,23.000,66.000,76.000,80.000,70.000,72.000,63.000,45.000,35.000,69.000,74.000,74.000,76.000,81.000}
-62.202 LMS_LASER_2D_RIGHT LMS2 ID=3943,time=1225719873.853998,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=32,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.199,17.811,14.610,12.355,10.726,9.585,8.724,7.855,7.221,6.714,6.190,5.831,5.441,5.111,4.791,4.561,4.283,4.045,3.864,3.660,3.503,3.315,3.182,3.017,2.915,2.804,2.657,2.589,2.525,2.459,2.371,2.301,2.190,2.130,2.079,2.028,1.970,1.919,1.866,1.821,1.785,1.752,1.707,1.669,1.631,1.595,1.560,1.551,1.518,1.485,1.459,1.422,1.392,1.369,1.351,1.324,1.322,1.301,1.279,1.267,1.252,1.253,1.243,1.258,1.262,1.272,1.272,1.250,1.241,1.235,1.207,1.206,1.189,1.170,1.171,1.162,1.145,1.110,1.100,1.096,1.075,1.066,1.095,1.085,1.074,1.033,1.029,1.013,1.019,1.027,1.029},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,2.000,59.000,118.000,99.000,77.000,64.000,56.000,58.000,57.000,63.000,67.000,67.000,69.000,69.000,71.000,71.000,74.000,74.000,75.000,75.000,77.000,78.000,78.000,77.000,80.000,80.000,73.000,78.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,78.000,78.000,78.000,76.000,78.000,79.000,77.000,77.000,72.000,75.000,76.000,76.000,74.000,60.000,65.000,72.000,75.000,72.000,73.000,72.000,66.000,61.000,54.000,57.000,68.000,68.000,61.000,68.000,66.000,66.000,64.000,52.000,48.000,35.000,28.000,26.000,25.000,26.000,28.000,42.000,43.000,36.000,28.000,25.000,27.000,29.000,32.000,37.000}
-62.215 LMS_LASER_2D_LEFT LMS1 ID=4071,time=1225719873.861814,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=68,Range=[181]{1.045,1.046,1.051,1.066,1.067,1.081,1.086,1.090,1.111,1.115,1.129,1.133,1.156,1.158,1.182,1.186,1.216,1.214,1.233,1.251,1.255,1.272,1.287,1.305,1.320,1.346,1.347,1.359,1.383,1.410,1.426,1.452,1.469,1.488,1.503,1.532,1.561,1.586,1.607,1.632,1.669,1.697,1.727,1.768,1.800,1.834,1.871,1.915,1.969,2.006,2.058,2.102,2.143,2.190,2.237,2.300,2.356,2.419,2.471,2.566,2.630,2.702,2.745,2.854,2.900,2.900,2.903,2.994,3.150,3.249,3.351,3.443,3.586,3.770,3.940,4.172,4.215,4.237,4.229,4.236,4.284,4.308,4.312,4.305,4.312,4.327,4.308,4.330,4.365,4.402,4.401,4.413,4.451,4.447,4.442,4.439,4.442,4.440,4.440,4.451,4.451,4.448,4.449,4.458,4.465,4.466,4.482,4.482,4.485,4.498,4.508,4.511,4.519,4.528,4.533,4.551,4.564,4.573,4.580,4.597,4.608,4.619,3.268,3.328,3.271,3.396,4.685,4.693,4.709,3.267,3.141,3.078,3.083,3.098,3.197,3.188,4.840,4.858,3.083,2.927,2.729,2.593,2.581,2.617,2.732,2.925,2.910,2.997,2.889,2.972,2.832,2.698,2.725,2.787,2.763,2.793,3.025,2.998,2.938,2.626,1.970,1.991,2.451,2.405,2.443,2.467,2.503,2.525,2.558,2.550,2.474,2.353,2.347,2.422,2.540,2.353,2.351,2.346,2.333,2.423,2.477},Reflectance=[181]{37.000,41.000,48.000,42.000,43.000,45.000,44.000,46.000,44.000,46.000,44.000,47.000,45.000,47.000,45.000,48.000,45.000,49.000,45.000,45.000,48.000,48.000,47.000,47.000,50.000,53.000,54.000,55.000,54.000,54.000,54.000,54.000,54.000,58.000,57.000,55.000,56.000,56.000,58.000,57.000,57.000,58.000,56.000,58.000,56.000,55.000,59.000,55.000,57.000,54.000,55.000,55.000,58.000,60.000,58.000,61.000,59.000,60.000,55.000,42.000,46.000,54.000,57.000,51.000,53.000,49.000,54.000,54.000,49.000,46.000,52.000,50.000,44.000,47.000,54.000,59.000,68.000,74.000,75.000,72.000,73.000,74.000,75.000,76.000,75.000,75.000,74.000,73.000,73.000,76.000,78.000,76.000,76.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,80.000,78.000,76.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,27.000,98.000,72.000,98.000,77.000,77.000,76.000,117.000,91.000,78.000,77.000,76.000,101.000,13.000,79.000,77.000,114.000,79.000,104.000,38.000,61.000,64.000,29.000,56.000,50.000,115.000,75.000,99.000,78.000,71.000,73.000,82.000,65.000,67.000,51.000,55.000,41.000,71.000,65.000,39.000,47.000,62.000,75.000,74.000,54.000,48.000,75.000,78.000,79.000,69.000,68.000,65.000,42.000,27.000,64.000,70.000,68.000,76.000,79.000}
-62.215 LMS_LASER_2D_RIGHT LMS2 ID=3944,time=1225719873.867330,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=33,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,17.157,14.205,12.052,10.538,9.520,8.620,7.791,7.143,6.651,6.154,5.821,5.407,5.068,4.766,4.518,4.256,4.019,3.838,3.653,3.470,3.307,3.159,3.000,2.906,2.786,2.663,2.595,2.525,2.451,2.372,2.301,2.200,2.130,2.072,2.028,1.969,1.927,1.875,1.824,1.788,1.741,1.716,1.668,1.613,1.563,1.545,1.535,1.508,1.479,1.448,1.422,1.392,1.363,1.336,1.317,1.305,1.289,1.276,1.264,1.253,1.267,1.259,1.257,1.256,1.271,1.258,1.237,1.235,1.239,1.223,1.205,1.201,1.173,1.149,1.147,1.151,1.118,1.091,1.087,1.081,1.069,1.094,1.083,1.078,1.061,1.021,1.022,1.020,1.022,1.022},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,78.000,117.000,92.000,74.000,62.000,57.000,57.000,57.000,63.000,66.000,66.000,69.000,69.000,71.000,72.000,74.000,74.000,75.000,76.000,78.000,78.000,76.000,78.000,80.000,80.000,75.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,76.000,74.000,74.000,79.000,78.000,78.000,76.000,72.000,75.000,75.000,75.000,74.000,71.000,72.000,75.000,74.000,73.000,66.000,68.000,65.000,63.000,57.000,67.000,74.000,71.000,64.000,66.000,65.000,61.000,56.000,40.000,45.000,43.000,29.000,27.000,26.000,25.000,28.000,41.000,41.000,42.000,35.000,25.000,29.000,30.000,31.000,35.000}
-62.226 LMS_LASER_2D_LEFT LMS1 ID=4072,time=1225719873.875149,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=69,Range=[181]{1.043,1.046,1.060,1.063,1.071,1.085,1.103,1.097,1.107,1.121,1.134,1.140,1.157,1.170,1.182,1.194,1.208,1.221,1.234,1.251,1.266,1.273,1.291,1.321,1.334,1.340,1.355,1.374,1.397,1.417,1.425,1.453,1.470,1.489,1.510,1.548,1.561,1.586,1.617,1.634,1.674,1.700,1.725,1.774,1.797,1.840,1.876,1.913,1.965,2.010,2.057,2.101,2.150,2.200,2.252,2.308,2.363,2.428,2.491,2.572,2.637,2.713,2.771,2.865,2.898,2.897,2.906,3.039,3.185,3.258,3.367,3.449,3.613,3.797,3.967,4.161,4.228,4.228,4.223,4.239,4.282,4.309,4.312,4.306,4.311,4.321,4.307,4.333,4.374,4.401,4.399,4.412,4.440,4.438,4.430,4.430,4.439,4.439,4.444,4.446,4.448,4.448,4.458,4.458,4.464,4.465,4.479,4.479,4.489,4.498,4.499,4.509,4.518,4.528,4.541,4.550,4.562,4.572,4.577,4.589,4.608,3.306,3.361,3.245,3.330,3.298,4.685,4.695,4.711,3.094,3.196,3.145,3.103,3.087,3.226,4.828,4.845,3.296,3.004,2.942,3.059,2.562,2.583,2.638,2.923,2.951,2.979,2.974,2.981,3.029,2.744,2.696,2.759,2.778,2.763,2.821,3.115,2.884,2.824,2.097,1.988,2.552,2.408,2.413,2.421,2.449,2.440,2.490,2.524,2.480,2.510,2.388,2.378,2.417,2.503,5.168,2.377,2.319,2.327,2.417,2.618},Reflectance=[181]{39.000,41.000,36.000,45.000,46.000,39.000,40.000,46.000,46.000,44.000,43.000,45.000,45.000,44.000,45.000,48.000,45.000,49.000,47.000,46.000,46.000,49.000,49.000,45.000,48.000,51.000,53.000,54.000,52.000,54.000,54.000,54.000,54.000,55.000,56.000,54.000,56.000,60.000,54.000,58.000,59.000,59.000,59.000,56.000,55.000,54.000,58.000,55.000,55.000,56.000,54.000,59.000,58.000,56.000,59.000,61.000,59.000,60.000,52.000,41.000,44.000,55.000,53.000,49.000,52.000,55.000,55.000,50.000,48.000,46.000,48.000,44.000,48.000,51.000,55.000,59.000,69.000,74.000,73.000,70.000,72.000,75.000,75.000,76.000,75.000,73.000,74.000,71.000,73.000,75.000,77.000,76.000,76.000,78.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,76.000,76.000,77.000,77.000,76.000,77.000,78.000,8.000,106.000,75.000,83.000,28.000,77.000,77.000,77.000,33.000,108.000,87.000,75.000,75.000,112.000,79.000,78.000,33.000,80.000,78.000,115.000,33.000,58.000,30.000,55.000,96.000,105.000,101.000,100.000,103.000,74.000,70.000,78.000,68.000,65.000,59.000,63.000,61.000,63.000,57.000,71.000,36.000,55.000,73.000,73.000,71.000,64.000,60.000,73.000,78.000,72.000,42.000,71.000,67.000,20.000,84.000,49.000,55.000,67.000,75.000,74.000}
-62.239 DESIRED_THRUST iJoystick 85.5708487197
-62.239 DESIRED_RUDDER iJoystick 2.05999938963
-62.226 LMS_LASER_2D_RIGHT LMS2 ID=3945,time=1225719873.880660,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=34,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.804,13.911,11.803,10.339,9.391,8.564,7.745,7.101,6.571,6.098,5.742,5.363,5.024,4.758,4.484,4.239,3.983,3.822,3.610,3.424,3.302,3.127,2.986,2.873,2.769,2.678,2.587,2.497,2.434,2.364,2.292,2.192,2.122,2.072,2.021,1.962,1.927,1.856,1.824,1.777,1.741,1.697,1.650,1.599,1.565,1.558,1.537,1.508,1.477,1.445,1.409,1.396,1.375,1.344,1.320,1.306,1.289,1.281,1.267,1.253,1.244,1.252,1.250,1.267,1.266,1.265,1.242,1.241,1.235,1.222,1.191,1.192,1.174,1.147,1.144,1.145,1.146,1.128,1.120,1.065,1.084,1.093,1.082,1.072,1.058,1.031,1.022,1.032,1.032,1.031},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,90.000,116.000,88.000,71.000,63.000,56.000,57.000,59.000,63.000,66.000,67.000,68.000,69.000,71.000,73.000,74.000,74.000,75.000,76.000,78.000,79.000,78.000,78.000,80.000,80.000,80.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,79.000,80.000,79.000,79.000,79.000,78.000,77.000,74.000,78.000,79.000,78.000,77.000,75.000,75.000,77.000,75.000,74.000,75.000,73.000,76.000,77.000,75.000,74.000,74.000,71.000,68.000,59.000,59.000,63.000,70.000,68.000,61.000,65.000,69.000,61.000,46.000,40.000,44.000,44.000,40.000,55.000,51.000,26.000,30.000,44.000,42.000,40.000,34.000,29.000,29.000,33.000,34.000,38.000}
-62.238 LMS_LASER_2D_LEFT LMS1 ID=4073,time=1225719873.888484,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=70,Range=[181]{1.041,1.052,1.054,1.067,1.073,1.078,1.098,1.107,1.109,1.125,1.139,1.143,1.163,1.174,1.185,1.191,1.208,1.224,1.234,1.251,1.267,1.284,1.291,1.313,1.329,1.353,1.361,1.379,1.393,1.425,1.434,1.459,1.478,1.489,1.517,1.537,1.563,1.599,1.621,1.639,1.672,1.707,1.748,1.774,1.808,1.844,1.878,1.928,1.981,2.012,2.075,2.116,2.160,2.207,2.259,2.308,2.373,2.435,2.506,2.583,2.657,2.724,2.760,2.877,2.899,2.887,2.909,3.069,3.199,3.277,3.383,3.473,3.633,3.837,4.016,4.166,4.226,4.228,4.232,4.252,4.283,4.309,4.301,4.301,4.314,4.319,4.311,4.334,4.374,4.393,4.388,4.420,4.442,4.438,4.439,4.439,4.431,4.439,4.439,4.437,4.451,4.448,4.458,4.457,4.465,4.466,4.475,4.481,4.491,4.491,4.501,4.517,4.527,4.533,4.540,4.552,4.561,4.570,4.587,4.591,4.606,3.265,3.314,3.303,3.460,4.670,4.687,4.696,4.708,4.728,3.134,3.193,3.098,3.123,3.113,4.820,3.397,3.320,2.978,2.941,3.028,2.566,2.611,4.204,3.000,2.881,2.891,2.901,3.009,2.900,2.689,2.706,2.770,2.789,2.860,3.063,3.055,2.874,2.209,1.932,3.184,5.481,2.422,2.425,2.431,2.402,2.407,2.429,2.417,2.375,2.420,2.405,2.370,2.426,5.094,5.131,5.094,2.323,2.333,2.566,2.617},Reflectance=[181]{43.000,40.000,40.000,43.000,45.000,44.000,45.000,41.000,47.000,47.000,45.000,43.000,44.000,45.000,43.000,46.000,50.000,45.000,47.000,46.000,45.000,50.000,49.000,47.000,50.000,49.000,52.000,52.000,54.000,54.000,54.000,53.000,54.000,59.000,56.000,57.000,57.000,54.000,56.000,56.000,55.000,54.000,57.000,56.000,55.000,56.000,59.000,54.000,54.000,57.000,55.000,54.000,58.000,60.000,59.000,63.000,58.000,55.000,48.000,45.000,45.000,56.000,56.000,50.000,52.000,55.000,57.000,48.000,46.000,50.000,47.000,46.000,49.000,50.000,57.000,63.000,71.000,74.000,73.000,71.000,72.000,75.000,75.000,75.000,73.000,72.000,72.000,72.000,73.000,76.000,77.000,76.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,77.000,76.000,77.000,77.000,77.000,76.000,78.000,77.000,27.000,93.000,81.000,108.000,78.000,78.000,78.000,76.000,77.000,39.000,83.000,76.000,83.000,36.000,78.000,6.000,99.000,78.000,78.000,118.000,58.000,67.000,103.000,118.000,75.000,76.000,76.000,102.000,104.000,71.000,70.000,68.000,65.000,72.000,65.000,66.000,45.000,66.000,30.000,56.000,66.000,57.000,72.000,74.000,73.000,72.000,60.000,59.000,68.000,52.000,63.000,66.000,59.000,73.000,84.000,75.000,59.000,63.000,58.000,62.000}
-62.238 LMS_LASER_2D_RIGHT LMS2 ID=3946,time=1225719873.893989,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=35,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.506,23.426,16.546,13.470,11.534,10.212,9.268,8.422,7.609,6.993,6.512,6.071,5.672,5.336,4.979,4.724,4.448,4.221,3.920,3.775,3.566,3.415,3.281,3.116,2.966,2.853,2.749,2.654,2.570,2.477,2.424,2.338,2.275,2.180,2.113,2.063,2.012,1.955,1.918,1.866,1.829,1.785,1.739,1.687,1.639,1.611,1.590,1.551,1.527,1.498,1.472,1.439,1.405,1.387,1.366,1.332,1.305,1.297,1.289,1.275,1.263,1.253,1.252,1.248,1.269,1.271,1.278,1.287,1.259,1.250,1.232,1.212,1.197,1.195,1.168,1.141,1.140,1.150,1.141,1.116,1.110,1.112,1.086,1.090,1.079,1.071,1.071,1.047,1.044,1.039,1.022,1.020},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,3.000,97.000,118.000,86.000,69.000,60.000,57.000,56.000,60.000,64.000,67.000,68.000,68.000,67.000,71.000,72.000,74.000,76.000,79.000,76.000,78.000,78.000,78.000,80.000,79.000,80.000,81.000,81.000,80.000,80.000,81.000,81.000,79.000,80.000,81.000,81.000,81.000,80.000,80.000,79.000,79.000,79.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,76.000,74.000,76.000,75.000,72.000,71.000,73.000,77.000,78.000,77.000,77.000,71.000,65.000,56.000,53.000,48.000,48.000,60.000,60.000,60.000,64.000,66.000,55.000,43.000,38.000,40.000,43.000,41.000,61.000,62.000,44.000,31.000,42.000,40.000,45.000,42.000,38.000,37.000,35.000,32.000,34.000}
-62.250 LMS_LASER_2D_LEFT LMS1 ID=4074,time=1225719873.901816,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=71,Range=[181]{1.041,1.055,1.054,1.071,1.077,1.088,1.098,1.098,1.115,1.123,1.141,1.152,1.160,1.169,1.182,1.200,1.201,1.227,1.242,1.252,1.252,1.281,1.296,1.319,1.328,1.352,1.356,1.379,1.391,1.408,1.433,1.454,1.471,1.491,1.521,1.549,1.575,1.593,1.617,1.646,1.682,1.706,1.739,1.781,1.806,1.855,1.885,1.929,1.985,2.023,2.077,2.119,2.167,2.210,2.267,2.326,2.381,2.453,2.524,2.593,2.663,2.738,2.804,2.883,2.898,2.888,2.920,3.085,3.210,3.287,3.383,3.492,3.676,3.876,4.051,4.189,4.229,4.226,4.231,4.254,4.292,4.309,4.304,4.301,4.310,4.321,4.305,4.346,4.384,4.395,4.395,4.427,4.441,4.437,4.436,4.437,4.439,4.436,4.439,4.439,4.448,4.448,4.456,4.456,4.466,4.467,4.475,4.482,4.491,4.490,4.500,4.517,4.526,4.535,4.540,4.550,4.562,4.571,4.588,4.592,4.607,3.262,3.388,3.399,4.662,4.670,4.680,4.696,4.712,4.731,3.288,3.166,3.149,3.188,3.259,4.826,3.321,3.221,2.965,2.939,2.823,2.574,2.793,3.972,2.985,2.892,2.899,2.911,3.044,2.890,2.712,2.743,2.842,2.852,3.103,3.006,2.780,3.126,2.149,3.155,3.161,2.499,2.453,2.448,2.396,2.383,2.396,2.442,2.375,2.347,2.347,2.442,2.370,2.466,5.086,5.054,2.443,2.359,2.362,2.677,2.628},Reflectance=[181]{43.000,41.000,46.000,41.000,39.000,35.000,41.000,46.000,45.000,46.000,42.000,43.000,43.000,43.000,45.000,47.000,51.000,43.000,45.000,47.000,51.000,48.000,51.000,50.000,49.000,52.000,54.000,52.000,53.000,53.000,53.000,55.000,55.000,56.000,54.000,55.000,58.000,59.000,58.000,55.000,55.000,57.000,57.000,60.000,59.000,56.000,58.000,58.000,56.000,54.000,56.000,55.000,57.000,61.000,58.000,61.000,58.000,55.000,48.000,42.000,44.000,47.000,49.000,50.000,52.000,55.000,54.000,48.000,48.000,51.000,47.000,47.000,51.000,49.000,60.000,60.000,72.000,74.000,72.000,72.000,73.000,75.000,76.000,75.000,72.000,73.000,73.000,72.000,73.000,76.000,76.000,75.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,77.000,77.000,77.000,78.000,77.000,26.000,106.000,100.000,78.000,78.000,78.000,78.000,77.000,75.000,103.000,78.000,88.000,108.000,3.000,78.000,26.000,107.000,77.000,77.000,106.000,67.000,122.000,103.000,95.000,76.000,75.000,76.000,109.000,120.000,70.000,71.000,74.000,74.000,102.000,70.000,62.000,43.000,83.000,51.000,39.000,14.000,55.000,64.000,65.000,70.000,71.000,46.000,55.000,68.000,43.000,58.000,65.000,45.000,70.000,74.000,43.000,57.000,42.000,42.000,65.000}
-62.251 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.5394,18.8506,-0.8137},Vel=[3x1]{-0.7971,-0.7532,-1.0256},Raw=[2x1]{20.4390,-0.8137},time=1225719873.89831757545471,Speed=1.09663853275313,Pitch=0.00448670746768,Roll=0.03140695227374,PitchDot=0.00448670746768,RollDot=0.00060570550814
-62.251 ODOMETRY_POSE iPlatform Pose=[3x1]{4.5394,18.8506,-0.8134},Vel=[3x1]{-0.7971,-0.7532,-1.0256},Raw=[2x1]{20.4390,-0.8137},time=1225719873.8983,Speed=1.0966,Pitch=-0.0197,Roll=0.0248,PitchDot=0.0018,RollDot=0.0042
-62.263 DESIRED_THRUST iJoystick 84.5393230995
-62.263 DESIRED_RUDDER iJoystick 2.05999938963
-62.287 DESIRED_THRUST iJoystick 84.5393230995
-62.287 DESIRED_RUDDER iJoystick 2.05999938963
-62.262 LMS_LASER_2D_LEFT LMS1 ID=4075,time=1225719873.915148,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=72,Range=[181]{1.044,1.059,1.057,1.064,1.082,1.088,1.098,1.102,1.110,1.126,1.141,1.149,1.168,1.174,1.181,1.208,1.213,1.237,1.234,1.259,1.268,1.295,1.294,1.324,1.334,1.347,1.365,1.389,1.402,1.419,1.428,1.459,1.480,1.504,1.530,1.555,1.579,1.602,1.627,1.657,1.690,1.723,1.760,1.788,1.815,1.866,1.895,1.941,1.991,2.035,2.091,2.134,2.176,2.222,2.293,2.331,2.392,2.462,2.545,2.608,2.679,2.751,2.845,2.889,2.894,2.892,2.962,3.112,3.233,3.304,3.409,3.531,3.703,3.903,4.077,4.183,4.233,4.224,4.231,4.263,4.292,4.309,4.301,4.311,4.310,4.314,4.312,4.350,4.384,4.398,4.392,4.436,4.442,4.436,4.436,4.436,4.435,4.434,4.438,4.439,4.448,4.447,4.456,4.455,4.466,4.466,4.474,4.483,4.491,4.488,4.508,4.515,4.524,4.533,4.541,4.550,4.561,4.572,4.581,4.590,4.608,4.623,3.369,3.370,4.655,4.670,4.680,4.697,4.711,4.726,3.281,3.253,3.206,3.296,3.161,4.828,3.134,3.145,3.008,2.899,2.601,2.610,2.826,3.863,2.998,2.967,2.980,2.996,2.957,2.782,2.737,2.890,2.878,2.959,2.918,2.949,2.808,3.196,3.080,3.098,2.522,2.471,2.480,2.491,2.415,2.391,2.411,2.443,2.349,2.297,2.313,2.395,2.370,2.607,5.090,2.427,2.416,5.168,2.668,2.636,2.582},Reflectance=[181]{44.000,39.000,47.000,46.000,42.000,41.000,45.000,48.000,48.000,43.000,41.000,45.000,43.000,45.000,50.000,45.000,49.000,43.000,47.000,46.000,46.000,45.000,54.000,48.000,48.000,54.000,54.000,52.000,54.000,55.000,55.000,53.000,55.000,54.000,54.000,57.000,56.000,56.000,55.000,56.000,58.000,57.000,54.000,59.000,59.000,57.000,58.000,56.000,55.000,56.000,54.000,54.000,58.000,55.000,54.000,60.000,59.000,55.000,41.000,41.000,43.000,44.000,48.000,52.000,50.000,53.000,47.000,48.000,47.000,47.000,46.000,47.000,48.000,49.000,56.000,65.000,73.000,73.000,72.000,72.000,73.000,75.000,75.000,75.000,72.000,73.000,73.000,71.000,73.000,77.000,75.000,75.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,77.000,77.000,77.000,77.000,78.000,77.000,15.000,17.000,79.000,78.000,78.000,78.000,77.000,76.000,111.000,104.000,109.000,118.000,20.000,78.000,30.000,87.000,90.000,78.000,72.000,72.000,108.000,91.000,92.000,94.000,99.000,98.000,133.000,69.000,72.000,96.000,74.000,76.000,66.000,56.000,72.000,61.000,65.000,62.000,47.000,56.000,55.000,37.000,46.000,67.000,70.000,27.000,56.000,73.000,70.000,68.000,62.000,2.000,72.000,32.000,54.000,86.000,30.000,69.000,69.000}
-62.262 LMS_LASER_2D_RIGHT LMS2 ID=3947,time=1225719873.907329,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=36,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.463,20.973,15.908,12.954,11.166,10.045,9.161,8.253,7.500,6.922,6.442,6.007,5.563,5.274,4.934,4.656,4.422,4.172,3.896,3.724,3.528,3.395,3.229,3.100,2.934,2.832,2.731,2.653,2.560,2.474,2.407,2.338,2.265,2.165,2.096,2.044,1.977,1.937,1.912,1.858,1.821,1.779,1.733,1.692,1.643,1.618,1.573,1.536,1.526,1.490,1.461,1.437,1.404,1.376,1.351,1.303,1.277,1.278,1.268,1.263,1.265,1.255,1.266,1.264,1.274,1.283,1.292,1.277,1.260,1.243,1.225,1.205,1.204,1.198,1.159,1.141,1.144,1.140,1.145,1.124,1.110,1.112,1.084,1.095,1.081,1.074,1.060,1.052,1.025,1.025,1.019,1.020},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,15.000,116.000,119.000,84.000,65.000,58.000,58.000,55.000,61.000,64.000,66.000,71.000,70.000,67.000,73.000,73.000,75.000,77.000,79.000,76.000,78.000,79.000,78.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,79.000,80.000,79.000,77.000,72.000,77.000,74.000,77.000,79.000,78.000,77.000,76.000,76.000,75.000,74.000,68.000,68.000,71.000,76.000,77.000,77.000,74.000,65.000,58.000,51.000,51.000,47.000,52.000,60.000,61.000,60.000,65.000,63.000,52.000,41.000,42.000,43.000,38.000,35.000,53.000,54.000,37.000,34.000,45.000,46.000,46.000,41.000,37.000,30.000,32.000,32.000,40.000}
-62.274 LMS_LASER_2D_RIGHT LMS2 ID=3948,time=1225719873.920666,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=37,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.503,18.639,15.431,12.740,10.926,9.829,8.964,8.074,7.406,6.869,6.366,5.911,5.436,5.184,4.890,4.606,4.340,4.062,3.891,3.734,3.513,3.355,3.195,3.023,2.894,2.824,2.705,2.634,2.543,2.457,2.381,2.320,2.247,2.165,2.095,2.020,1.965,1.939,1.901,1.855,1.815,1.768,1.732,1.687,1.637,1.603,1.565,1.527,1.511,1.480,1.462,1.434,1.416,1.373,1.351,1.304,1.269,1.264,1.266,1.261,1.251,1.252,1.258,1.260,1.278,1.281,1.288,1.265,1.253,1.243,1.229,1.221,1.207,1.196,1.158,1.143,1.143,1.132,1.143,1.124,1.115,1.081,1.097,1.088,1.077,1.071,1.061,1.055,1.037,1.045,1.027,1.029},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,21.000,24.000,120.000,109.000,82.000,64.000,58.000,59.000,56.000,61.000,65.000,67.000,74.000,70.000,69.000,73.000,74.000,76.000,75.000,77.000,77.000,79.000,79.000,79.000,79.000,81.000,80.000,80.000,81.000,79.000,80.000,81.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,79.000,80.000,79.000,79.000,78.000,77.000,78.000,74.000,74.000,77.000,78.000,78.000,77.000,74.000,75.000,73.000,70.000,71.000,74.000,78.000,79.000,78.000,72.000,67.000,56.000,49.000,46.000,45.000,58.000,61.000,61.000,54.000,58.000,60.000,51.000,42.000,43.000,43.000,32.000,41.000,53.000,46.000,29.000,42.000,45.000,44.000,45.000,45.000,40.000,37.000,37.000,37.000,42.000}
-62.286 LMS_LASER_2D_RIGHT LMS2 ID=3949,time=1225719873.934004,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=38,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.550,17.948,14.870,12.466,10.698,9.655,8.809,7.920,7.292,6.732,6.254,5.822,5.409,5.120,4.828,4.536,4.293,4.060,3.880,3.673,3.484,3.331,3.193,2.955,2.898,2.796,2.696,2.595,2.513,2.415,2.371,2.311,2.227,2.147,2.087,2.005,1.962,1.928,1.892,1.850,1.806,1.759,1.707,1.669,1.624,1.603,1.554,1.529,1.507,1.475,1.448,1.421,1.396,1.373,1.342,1.314,1.289,1.265,1.259,1.253,1.251,1.250,1.266,1.259,1.278,1.284,1.285,1.263,1.240,1.243,1.242,1.227,1.190,1.177,1.154,1.135,1.137,1.131,1.139,1.122,1.103,1.088,1.103,1.076,1.073,1.067,1.058,1.046,1.043,1.038,1.027,1.022},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,13.000,59.000,115.000,100.000,79.000,62.000,57.000,58.000,58.000,63.000,66.000,67.000,72.000,71.000,70.000,73.000,73.000,75.000,75.000,77.000,77.000,77.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,79.000,78.000,73.000,74.000,69.000,73.000,72.000,71.000,73.000,75.000,73.000,71.000,72.000,75.000,76.000,72.000,70.000,68.000,59.000,56.000,49.000,44.000,52.000,57.000,66.000,61.000,52.000,50.000,56.000,54.000,39.000,41.000,42.000,32.000,37.000,52.000,51.000,31.000,44.000,41.000,46.000,41.000,43.000,37.000,36.000,38.000,37.000,38.000}
-62.287 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.5713,18.8807,-0.8120},Vel=[3x1]{-0.8128,-0.7706,-2.9487},Raw=[2x1]{20.4829,-0.8120},time=1225719873.93437051773071,Speed=1.12000233638036,Pitch=0.00673006120152,Roll=0.03589365974142,PitchDot=0.00224335373384,RollDot=0.00076274026951
-62.287 ODOMETRY_POSE iPlatform Pose=[3x1]{4.5713,18.8807,-0.8116},Vel=[3x1]{-0.8128,-0.7706,-2.9487},Raw=[2x1]{20.4829,-0.8120},time=1225719873.9344,Speed=1.1200,Pitch=-0.0214,Roll=0.0296,PitchDot=-0.0023,RollDot=-0.0003
-62.295 DESIRED_RUDDER iRemote 0
-62.295 DESIRED_THRUST iRemote 0
-62.295 DESIRED_ELEVATOR iRemote 0
-62.311 DESIRED_THRUST iJoystick 84.5393230995
-62.311 DESIRED_RUDDER iJoystick 2.05999938963
-62.286 LMS_LASER_2D_LEFT LMS1 ID=4076,time=1225719873.928490,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=73,Range=[181]{1.042,1.056,1.064,1.071,1.080,1.088,1.099,1.108,1.113,1.132,1.140,1.143,1.169,1.178,1.182,1.204,1.212,1.233,1.248,1.259,1.275,1.294,1.301,1.322,1.346,1.352,1.374,1.382,1.400,1.425,1.443,1.470,1.481,1.505,1.530,1.559,1.579,1.607,1.638,1.662,1.702,1.729,1.764,1.790,1.827,1.875,1.902,1.954,2.006,2.049,2.091,2.143,2.196,2.254,2.304,2.348,2.406,2.478,2.556,2.624,2.690,2.776,2.852,2.887,2.893,2.900,2.982,3.145,3.250,3.328,3.428,3.569,3.740,3.927,4.113,4.226,4.227,4.224,4.233,4.273,4.297,4.298,4.298,4.296,4.313,4.313,4.319,4.350,4.388,4.395,4.401,4.436,4.443,4.435,4.442,4.441,4.442,4.443,4.438,4.439,4.448,4.446,4.448,4.457,4.465,4.466,4.476,4.475,4.491,4.489,4.498,4.512,4.523,4.532,4.541,4.552,4.561,4.572,4.582,4.590,4.608,4.617,3.375,4.646,4.653,4.669,4.681,4.690,4.715,4.734,3.174,4.760,3.298,3.295,3.148,4.837,3.240,3.155,3.009,2.748,2.585,2.669,2.854,3.764,3.079,3.030,3.043,2.941,2.700,2.745,2.793,3.075,2.858,2.978,2.935,3.002,3.361,3.121,3.104,2.611,2.502,2.464,2.483,2.404,2.415,2.414,2.458,5.652,2.312,2.287,2.324,2.363,2.379,5.225,2.452,2.422,5.124,5.155,2.656,2.468,2.434},Reflectance=[181]{43.000,42.000,45.000,41.000,37.000,40.000,42.000,42.000,49.000,45.000,45.000,48.000,43.000,44.000,45.000,44.000,44.000,46.000,44.000,46.000,46.000,50.000,49.000,47.000,50.000,52.000,54.000,53.000,53.000,54.000,54.000,54.000,55.000,54.000,54.000,55.000,56.000,54.000,56.000,58.000,55.000,56.000,56.000,56.000,56.000,58.000,58.000,54.000,54.000,55.000,54.000,55.000,55.000,49.000,48.000,56.000,58.000,51.000,41.000,43.000,41.000,43.000,54.000,55.000,50.000,53.000,49.000,46.000,46.000,45.000,45.000,52.000,53.000,48.000,56.000,64.000,74.000,73.000,73.000,72.000,74.000,75.000,75.000,74.000,70.000,73.000,72.000,71.000,74.000,76.000,75.000,75.000,77.000,77.000,77.000,76.000,77.000,77.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,78.000,77.000,78.000,78.000,22.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,17.000,76.000,119.000,117.000,25.000,78.000,115.000,102.000,94.000,81.000,67.000,78.000,103.000,75.000,94.000,104.000,100.000,103.000,63.000,72.000,70.000,99.000,71.000,69.000,62.000,61.000,113.000,60.000,70.000,72.000,79.000,56.000,33.000,24.000,45.000,63.000,57.000,68.000,59.000,75.000,76.000,70.000,53.000,90.000,14.000,53.000,80.000,85.000,58.000,74.000,72.000}
-62.298 LMS_LASER_2D_LEFT LMS1 ID=4077,time=1225719873.941831,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=74,Range=[181]{1.051,1.061,1.072,1.075,1.083,1.088,1.108,1.119,1.120,1.141,1.149,1.160,1.171,1.187,1.193,1.208,1.213,1.232,1.251,1.264,1.286,1.295,1.312,1.326,1.338,1.362,1.385,1.400,1.408,1.421,1.442,1.470,1.494,1.512,1.535,1.572,1.590,1.614,1.632,1.670,1.698,1.727,1.771,1.804,1.837,1.875,1.918,1.971,2.007,2.052,2.107,2.153,2.204,2.259,2.325,2.363,2.417,2.497,2.568,2.634,2.704,2.783,2.845,2.884,2.889,2.901,3.029,3.183,3.265,3.337,3.451,3.599,3.770,3.931,4.137,4.219,4.227,4.225,4.232,4.273,4.298,4.301,4.301,4.308,4.322,4.300,4.318,4.360,4.391,4.396,4.401,4.438,4.441,4.441,4.441,4.449,4.441,4.443,4.439,4.440,4.440,4.449,4.447,4.455,4.463,4.465,4.475,4.484,4.481,4.490,4.508,4.516,4.521,4.532,4.543,4.552,4.562,4.573,4.591,4.592,4.607,4.612,3.376,4.644,4.653,4.672,4.681,4.698,4.716,4.733,4.741,4.763,3.140,3.295,3.153,4.832,3.239,2.971,2.957,2.654,2.598,2.711,2.963,3.752,3.842,3.724,3.067,2.810,2.852,2.933,3.208,2.893,2.905,2.960,2.966,3.214,3.257,3.115,3.124,3.108,3.154,2.530,2.512,2.417,2.438,2.475,2.495,5.647,2.302,2.295,2.329,2.348,2.440,5.250,2.419,5.114,5.159,5.160,2.416,2.366,2.349},Reflectance=[181]{39.000,44.000,45.000,43.000,38.000,46.000,42.000,39.000,44.000,42.000,45.000,43.000,40.000,44.000,43.000,46.000,49.000,46.000,45.000,44.000,45.000,46.000,45.000,49.000,50.000,49.000,51.000,53.000,53.000,55.000,53.000,54.000,53.000,54.000,56.000,53.000,58.000,57.000,57.000,58.000,58.000,60.000,55.000,54.000,57.000,58.000,57.000,54.000,55.000,56.000,54.000,55.000,55.000,47.000,44.000,55.000,59.000,51.000,43.000,40.000,43.000,51.000,55.000,53.000,52.000,53.000,49.000,47.000,46.000,46.000,44.000,53.000,55.000,58.000,56.000,69.000,74.000,73.000,73.000,72.000,75.000,75.000,75.000,74.000,71.000,72.000,72.000,71.000,75.000,76.000,75.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,76.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,76.000,20.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,77.000,38.000,116.000,26.000,77.000,115.000,51.000,84.000,81.000,69.000,81.000,99.000,74.000,87.000,100.000,82.000,94.000,101.000,96.000,103.000,76.000,72.000,62.000,60.000,101.000,49.000,64.000,71.000,58.000,54.000,32.000,26.000,35.000,34.000,49.000,45.000,69.000,67.000,75.000,75.000,68.000,27.000,90.000,26.000,76.000,86.000,82.000,69.000,73.000,68.000}
-62.298 LMS_LASER_2D_RIGHT LMS2 ID=3950,time=1225719873.947339,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=39,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,27.542,17.061,14.179,11.974,10.465,9.473,8.661,7.818,7.199,6.678,6.145,5.698,5.338,5.040,4.757,4.491,4.265,4.021,3.857,3.597,3.450,3.297,3.147,2.967,2.893,2.761,2.667,2.570,2.493,2.388,2.354,2.292,2.206,2.139,2.070,2.003,1.959,1.928,1.884,1.842,1.806,1.739,1.686,1.649,1.614,1.598,1.566,1.527,1.498,1.465,1.439,1.416,1.386,1.369,1.332,1.305,1.284,1.272,1.266,1.258,1.253,1.251,1.262,1.268,1.278,1.280,1.270,1.256,1.232,1.230,1.231,1.209,1.179,1.170,1.146,1.134,1.140,1.116,1.094,1.084,1.065,1.057,1.092,1.076,1.077,1.063,1.057,1.043,1.029,1.036,1.031,1.015},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,91.000,120.000,95.000,74.000,60.000,56.000,57.000,60.000,64.000,66.000,69.000,72.000,68.000,71.000,71.000,73.000,75.000,76.000,78.000,77.000,78.000,76.000,80.000,81.000,80.000,79.000,75.000,79.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,78.000,79.000,77.000,73.000,68.000,72.000,72.000,74.000,72.000,71.000,72.000,71.000,75.000,77.000,78.000,75.000,73.000,71.000,61.000,56.000,49.000,46.000,61.000,63.000,66.000,64.000,60.000,57.000,59.000,51.000,39.000,41.000,38.000,29.000,27.000,26.000,26.000,27.000,41.000,41.000,44.000,45.000,41.000,39.000,32.000,37.000,38.000,34.000}
-62.312 LMS_LASER_2D_LEFT LMS1 ID=4078,time=1225719873.955172,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=75,Range=[181]{1.058,1.067,1.070,1.082,1.086,1.089,1.106,1.114,1.127,1.132,1.144,1.160,1.171,1.183,1.191,1.210,1.219,1.242,1.253,1.268,1.280,1.305,1.318,1.332,1.342,1.370,1.385,1.401,1.418,1.433,1.452,1.477,1.495,1.523,1.538,1.566,1.598,1.614,1.645,1.672,1.705,1.742,1.776,1.815,1.849,1.878,1.929,1.973,2.024,2.063,2.108,2.157,2.223,2.284,2.342,2.398,2.431,2.510,2.577,2.652,2.727,2.804,2.847,2.884,2.872,2.910,3.045,3.210,3.280,3.347,3.489,3.638,3.815,3.965,4.162,4.229,4.225,4.225,4.238,4.282,4.301,4.301,4.296,4.306,4.316,4.305,4.327,4.364,4.395,4.388,4.410,4.437,4.437,4.448,4.446,4.439,4.442,4.437,4.442,4.439,4.438,4.448,4.448,4.455,4.459,4.469,4.476,4.482,4.482,4.490,4.504,4.514,4.521,4.532,4.541,4.553,4.564,4.572,4.583,4.598,4.607,3.399,4.636,4.649,4.654,4.672,4.691,4.691,4.716,4.726,4.740,4.761,3.145,3.295,3.148,3.245,4.848,2.847,2.764,2.620,2.613,2.843,3.908,3.817,3.913,3.606,2.972,2.897,3.165,3.216,3.106,2.841,2.945,2.968,3.002,3.256,3.233,3.115,3.141,3.143,2.572,2.511,2.522,2.504,5.604,2.490,2.467,2.385,2.334,2.323,2.334,2.454,5.253,5.298,5.131,5.126,5.150,2.436,2.373,2.372,2.381},Reflectance=[181]{38.000,43.000,44.000,41.000,44.000,45.000,45.000,45.000,48.000,46.000,43.000,43.000,44.000,41.000,46.000,47.000,48.000,45.000,47.000,46.000,48.000,51.000,49.000,47.000,48.000,48.000,51.000,54.000,51.000,53.000,54.000,53.000,54.000,55.000,58.000,54.000,54.000,57.000,55.000,59.000,57.000,58.000,53.000,55.000,54.000,59.000,54.000,55.000,55.000,57.000,55.000,57.000,51.000,41.000,40.000,54.000,57.000,50.000,47.000,40.000,42.000,56.000,56.000,50.000,55.000,57.000,49.000,48.000,48.000,47.000,45.000,47.000,59.000,54.000,59.000,72.000,73.000,73.000,72.000,72.000,75.000,75.000,76.000,74.000,71.000,73.000,72.000,72.000,76.000,77.000,75.000,75.000,75.000,76.000,75.000,76.000,77.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,77.000,76.000,76.000,76.000,76.000,76.000,77.000,78.000,77.000,78.000,77.000,77.000,17.000,78.000,79.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,76.000,26.000,117.000,27.000,3.000,77.000,122.000,81.000,72.000,70.000,109.000,81.000,78.000,96.000,101.000,86.000,103.000,95.000,94.000,88.000,69.000,69.000,69.000,64.000,114.000,54.000,66.000,56.000,57.000,64.000,67.000,55.000,26.000,64.000,52.000,32.000,31.000,71.000,73.000,67.000,56.000,88.000,92.000,76.000,79.000,86.000,33.000,69.000,74.000,74.000}
-62.323 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.6036,18.9115,-0.8100},Vel=[3x1]{-0.8060,-0.7672,-1.6667},Raw=[2x1]{20.5276,-0.8100},time=1225719873.97033858299255,Speed=1.11270114774685,Pitch=0.00673006120152,Roll=0.04038036720910,PitchDot=0.02916359853990,RollDot=0.00085247441886
-62.323 ODOMETRY_POSE iPlatform Pose=[3x1]{4.6036,18.9115,-0.8095},Vel=[3x1]{-0.8060,-0.7672,-1.6666},Raw=[2x1]{20.5276,-0.8100},time=1225719873.9703,Speed=1.1127,Pitch=-0.0246,Roll=0.0327,PitchDot=-0.0036,RollDot=0.0289
-62.335 DESIRED_THRUST iJoystick 84.5393230995
-62.335 DESIRED_RUDDER iJoystick 3.09152500992
-62.312 LMS_LASER_2D_RIGHT LMS2 ID=3951,time=1225719873.960674,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=40,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.783,13.591,11.634,10.249,9.335,8.543,7.682,7.060,6.555,6.062,5.631,5.301,4.981,4.681,4.447,4.203,3.995,3.840,3.602,3.440,3.298,3.120,2.970,2.864,2.758,2.656,2.562,2.488,2.403,2.348,2.283,2.197,2.130,2.051,1.983,1.941,1.918,1.866,1.824,1.785,1.729,1.688,1.640,1.606,1.581,1.567,1.526,1.490,1.456,1.442,1.414,1.384,1.350,1.323,1.297,1.288,1.275,1.259,1.250,1.247,1.251,1.256,1.257,1.277,1.281,1.263,1.248,1.230,1.227,1.219,1.201,1.192,1.171,1.140,1.132,1.130,1.107,1.090,1.084,1.058,1.054,1.082,1.071,1.065,1.069,1.054,1.044,1.031,1.008,1.018,1.015},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,97.000,125.000,92.000,72.000,58.000,55.000,56.000,60.000,65.000,68.000,69.000,70.000,69.000,71.000,72.000,74.000,75.000,76.000,77.000,77.000,78.000,79.000,81.000,80.000,79.000,79.000,68.000,78.000,79.000,81.000,80.000,79.000,80.000,79.000,79.000,79.000,80.000,80.000,80.000,79.000,78.000,79.000,78.000,79.000,79.000,78.000,72.000,69.000,72.000,77.000,76.000,69.000,72.000,72.000,73.000,76.000,75.000,76.000,76.000,75.000,70.000,63.000,59.000,48.000,50.000,62.000,65.000,64.000,61.000,62.000,57.000,57.000,48.000,38.000,42.000,35.000,29.000,27.000,28.000,26.000,27.000,36.000,42.000,46.000,44.000,42.000,39.000,36.000,30.000,35.000,36.000}
-62.326 LMS_LASER_2D_LEFT LMS1 ID=4079,time=1225719873.968513,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=76,Range=[181]{1.054,1.059,1.070,1.074,1.057,1.070,1.111,1.114,1.132,1.138,1.156,1.174,1.171,1.191,1.199,1.219,1.229,1.248,1.262,1.267,1.280,1.297,1.316,1.326,1.353,1.365,1.384,1.400,1.426,1.443,1.459,1.479,1.504,1.530,1.547,1.575,1.598,1.621,1.651,1.689,1.717,1.757,1.781,1.821,1.857,1.891,1.939,1.990,2.026,2.062,2.127,2.166,2.232,2.295,2.336,2.409,2.453,2.526,2.595,2.662,2.736,2.818,2.862,2.892,2.874,2.926,3.070,3.241,3.298,3.354,3.509,3.686,3.846,4.013,4.189,4.220,4.226,4.222,4.252,4.286,4.300,4.304,4.293,4.308,4.312,4.305,4.334,4.371,4.393,4.385,4.420,4.437,4.442,4.438,4.440,4.443,4.444,4.439,4.442,4.439,4.439,4.449,4.447,4.458,4.458,4.465,4.474,4.483,4.482,4.488,4.497,4.506,4.523,4.533,4.545,4.554,4.563,4.573,4.592,4.600,4.609,4.626,4.638,4.646,4.654,4.672,4.690,4.699,4.716,4.734,4.749,3.104,3.107,3.288,3.134,4.842,2.671,2.659,2.691,2.655,2.691,4.073,3.894,3.954,3.982,3.590,3.464,3.377,3.164,3.200,2.985,2.855,3.032,3.004,3.072,3.260,3.194,3.169,3.168,2.671,2.533,2.520,2.511,2.527,5.605,2.463,2.416,2.360,2.406,2.379,2.486,5.186,5.235,5.328,5.169,5.175,5.159,2.446,2.415,2.408,2.389},Reflectance=[181]{41.000,43.000,44.000,38.000,29.000,30.000,39.000,45.000,45.000,46.000,46.000,45.000,49.000,45.000,45.000,43.000,39.000,40.000,43.000,50.000,51.000,51.000,52.000,52.000,49.000,50.000,54.000,53.000,54.000,54.000,53.000,54.000,54.000,54.000,54.000,55.000,54.000,56.000,53.000,54.000,54.000,57.000,56.000,54.000,57.000,61.000,55.000,54.000,56.000,61.000,55.000,57.000,51.000,39.000,34.000,51.000,55.000,44.000,43.000,43.000,46.000,58.000,59.000,49.000,56.000,53.000,49.000,46.000,48.000,50.000,45.000,48.000,50.000,56.000,60.000,72.000,74.000,72.000,71.000,73.000,75.000,76.000,75.000,74.000,73.000,73.000,72.000,72.000,76.000,76.000,76.000,75.000,77.000,76.000,76.000,77.000,77.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,31.000,32.000,118.000,27.000,77.000,56.000,70.000,71.000,72.000,62.000,102.000,94.000,93.000,96.000,103.000,75.000,76.000,94.000,95.000,95.000,68.000,72.000,69.000,65.000,103.000,60.000,61.000,41.000,48.000,70.000,75.000,69.000,53.000,67.000,56.000,24.000,63.000,67.000,38.000,41.000,74.000,83.000,93.000,82.000,82.000,86.000,52.000,74.000,75.000,76.000}
-62.326 LMS_LASER_2D_RIGHT LMS2 ID=3952,time=1225719873.974011,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=41,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,27.898,-1.000,16.179,13.150,11.341,10.072,9.145,8.344,7.588,6.958,6.468,5.991,5.587,5.238,4.908,4.639,4.411,4.126,3.950,3.798,3.593,3.423,3.263,3.097,2.972,2.853,2.737,2.649,2.546,2.471,2.380,2.331,2.255,2.172,2.122,2.051,1.983,1.933,1.910,1.855,1.804,1.768,1.723,1.679,1.631,1.597,1.571,1.550,1.515,1.494,1.462,1.432,1.404,1.368,1.348,1.324,1.295,1.285,1.280,1.267,1.256,1.244,1.249,1.253,1.269,1.269,1.262,1.261,1.256,1.236,1.221,1.213,1.200,1.182,1.166,1.133,1.132,1.121,1.098,1.091,1.072,1.064,1.048,1.090,1.080,1.070,1.065,1.056,1.049,1.035,1.027,1.023,1.015},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,15.000,0.000,118.000,120.000,85.000,68.000,59.000,57.000,54.000,60.000,67.000,68.000,68.000,69.000,71.000,72.000,72.000,74.000,75.000,76.000,76.000,78.000,78.000,80.000,79.000,79.000,79.000,79.000,76.000,81.000,80.000,81.000,80.000,79.000,80.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,78.000,79.000,76.000,72.000,76.000,78.000,75.000,74.000,78.000,77.000,71.000,69.000,76.000,73.000,75.000,75.000,76.000,78.000,77.000,73.000,66.000,61.000,56.000,56.000,61.000,61.000,58.000,62.000,63.000,64.000,61.000,57.000,53.000,38.000,42.000,33.000,28.000,27.000,25.000,25.000,27.000,42.000,45.000,45.000,41.000,42.000,43.000,39.000,35.000,38.000,36.000}
-62.338 LMS_LASER_2D_LEFT LMS1 ID=4080,time=1225719873.981853,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=77,Range=[181]{1.058,1.068,1.077,1.070,1.064,1.073,1.083,1.131,1.132,1.149,1.155,1.165,1.181,1.185,1.206,1.217,1.236,1.247,1.259,1.269,1.289,1.307,1.316,1.342,1.356,1.370,1.382,1.409,1.426,1.446,1.461,1.486,1.511,1.530,1.556,1.578,1.608,1.629,1.658,1.695,1.724,1.757,1.787,1.821,1.861,1.912,1.955,1.990,2.036,2.080,2.127,2.186,2.243,2.311,2.361,2.423,2.467,2.540,2.612,2.678,2.745,2.831,2.864,2.892,2.879,2.957,3.113,3.252,3.314,3.385,3.547,3.719,3.895,4.043,4.200,4.220,4.225,4.219,4.252,4.281,4.298,4.301,4.293,4.307,4.315,4.307,4.340,4.371,4.392,4.384,4.424,4.430,4.432,4.439,4.433,4.442,4.437,4.438,4.439,4.440,4.448,4.449,4.448,4.461,4.463,4.464,4.463,4.476,4.481,4.495,4.498,4.510,4.520,4.534,4.544,4.556,4.566,4.581,4.591,4.599,4.618,4.635,4.638,4.646,4.662,4.672,4.691,4.699,4.716,4.734,3.281,3.184,3.219,3.255,3.095,2.674,2.658,2.687,2.762,2.646,2.778,3.629,3.805,4.089,3.987,3.630,3.431,3.275,3.266,2.978,2.824,2.875,3.135,3.188,3.072,3.287,3.154,3.169,3.148,3.260,2.527,2.524,2.517,2.510,2.443,2.422,2.359,2.355,2.448,6.266,5.288,5.158,5.233,5.100,5.112,5.210,5.102,2.433,2.414,2.440,2.387},Reflectance=[181]{43.000,39.000,44.000,32.000,26.000,27.000,29.000,46.000,45.000,45.000,46.000,46.000,46.000,43.000,46.000,42.000,43.000,49.000,46.000,47.000,48.000,48.000,48.000,48.000,50.000,52.000,53.000,54.000,54.000,51.000,54.000,54.000,53.000,54.000,54.000,56.000,54.000,55.000,56.000,57.000,58.000,61.000,58.000,54.000,55.000,54.000,54.000,54.000,56.000,57.000,55.000,54.000,51.000,38.000,35.000,53.000,54.000,45.000,39.000,43.000,46.000,56.000,60.000,50.000,55.000,52.000,44.000,47.000,48.000,48.000,45.000,44.000,46.000,50.000,62.000,72.000,73.000,72.000,71.000,72.000,75.000,75.000,75.000,74.000,74.000,74.000,71.000,72.000,75.000,76.000,77.000,76.000,76.000,76.000,77.000,77.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,77.000,76.000,77.000,78.000,76.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,79.000,119.000,97.000,112.000,113.000,31.000,53.000,72.000,73.000,80.000,65.000,56.000,27.000,99.000,101.000,101.000,107.000,76.000,78.000,86.000,82.000,69.000,65.000,72.000,101.000,65.000,102.000,58.000,57.000,38.000,13.000,64.000,73.000,74.000,58.000,47.000,62.000,46.000,67.000,61.000,60.000,80.000,65.000,81.000,29.000,34.000,84.000,68.000,54.000,63.000,64.000,83.000}
-62.359 DESIRED_THRUST iJoystick 84.5393230995
-62.359 DESIRED_RUDDER iJoystick 3.09152500992
-62.338 LMS_LASER_2D_RIGHT LMS2 ID=3953,time=1225719873.987346,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=42,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-6.000,-1.000,-6.000,-6.000,-6.000,-6.000,27.933,-1.000,15.824,12.914,11.076,9.909,8.991,8.190,7.479,6.870,6.334,5.911,5.537,5.201,4.863,4.614,4.250,4.090,3.923,3.748,3.551,3.372,3.225,3.076,2.936,2.822,2.724,2.631,2.533,2.453,2.382,2.312,2.238,2.156,2.114,2.040,1.977,1.935,1.889,1.845,1.785,1.749,1.698,1.671,1.636,1.589,1.569,1.541,1.514,1.475,1.454,1.433,1.396,1.370,1.353,1.315,1.303,1.280,1.271,1.268,1.258,1.251,1.256,1.251,1.268,1.262,1.283,1.273,1.252,1.232,1.221,1.209,1.197,1.192,1.176,1.133,1.128,1.112,1.104,1.077,1.074,1.054,1.083,1.086,1.078,1.067,1.060,1.052,1.044,1.031,1.019,1.019,0.979},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,17.000,0.000,122.000,113.000,83.000,65.000,59.000,57.000,54.000,62.000,69.000,67.000,70.000,68.000,70.000,72.000,77.000,76.000,75.000,76.000,77.000,79.000,80.000,79.000,79.000,80.000,81.000,79.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,78.000,79.000,79.000,79.000,79.000,77.000,76.000,78.000,78.000,78.000,76.000,78.000,77.000,73.000,72.000,74.000,74.000,75.000,74.000,73.000,76.000,75.000,70.000,63.000,60.000,56.000,53.000,43.000,51.000,61.000,67.000,63.000,61.000,60.000,50.000,43.000,38.000,42.000,32.000,28.000,27.000,26.000,27.000,36.000,44.000,45.000,43.000,41.000,42.000,39.000,36.000,35.000,35.000,28.000}
-62.350 LMS_LASER_2D_LEFT LMS1 ID=4081,time=1225719873.995193,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=78,Range=[181]{1.061,1.070,1.077,1.055,1.068,1.075,1.125,1.131,1.137,1.138,1.160,1.174,1.183,1.198,1.206,1.216,1.232,1.253,1.258,1.278,1.287,1.304,1.330,1.340,1.354,1.377,1.397,1.408,1.428,1.452,1.469,1.483,1.507,1.531,1.561,1.582,1.606,1.636,1.667,1.702,1.726,1.755,1.791,1.830,1.871,1.911,1.969,2.007,2.050,2.091,2.142,2.186,2.256,2.307,2.360,2.433,2.482,2.563,2.621,2.688,2.768,2.852,2.872,2.888,2.890,2.985,3.136,3.251,3.325,3.400,3.573,3.753,3.922,4.086,4.200,4.220,4.214,4.217,4.254,4.283,4.290,4.293,4.293,4.309,4.309,4.307,4.341,4.373,4.384,4.386,4.422,4.422,4.430,4.432,4.433,4.434,4.438,4.430,4.439,4.437,4.446,4.451,4.448,4.459,4.458,4.464,4.474,4.483,4.489,4.488,4.499,4.507,4.522,4.534,4.546,4.547,4.565,4.575,4.594,4.601,4.607,4.626,4.638,4.646,4.659,4.672,4.692,4.707,4.716,3.306,3.102,3.097,3.150,3.191,2.838,2.661,2.789,2.807,2.652,2.738,3.094,3.761,3.771,4.010,3.862,3.619,3.511,3.181,3.089,2.910,2.841,2.897,3.293,2.999,3.115,3.142,3.143,3.193,3.171,5.455,2.548,2.541,2.518,2.440,2.427,2.405,2.446,2.459,2.463,6.251,5.245,5.158,5.228,5.173,5.330,5.227,5.164,5.181,2.591,2.593,2.386},Reflectance=[181]{40.000,40.000,39.000,30.000,26.000,28.000,38.000,46.000,44.000,46.000,43.000,42.000,42.000,45.000,46.000,50.000,50.000,47.000,49.000,51.000,47.000,47.000,46.000,51.000,49.000,51.000,52.000,53.000,51.000,54.000,54.000,56.000,55.000,54.000,56.000,58.000,57.000,59.000,56.000,55.000,55.000,56.000,56.000,58.000,55.000,54.000,53.000,55.000,55.000,58.000,58.000,54.000,46.000,35.000,32.000,54.000,49.000,40.000,45.000,43.000,48.000,51.000,56.000,51.000,56.000,46.000,47.000,47.000,52.000,50.000,43.000,44.000,43.000,48.000,63.000,72.000,73.000,71.000,72.000,72.000,75.000,75.000,75.000,75.000,75.000,74.000,71.000,72.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,79.000,79.000,78.000,79.000,119.000,77.000,76.000,84.000,95.000,121.000,73.000,100.000,80.000,71.000,75.000,115.000,109.000,103.000,99.000,111.000,105.000,88.000,81.000,85.000,78.000,69.000,70.000,99.000,49.000,63.000,66.000,64.000,55.000,36.000,69.000,31.000,55.000,61.000,64.000,72.000,61.000,68.000,74.000,56.000,64.000,76.000,65.000,78.000,25.000,90.000,83.000,83.000,81.000,27.000,54.000,85.000}
-62.359 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.6276,18.9343,-0.8093},Vel=[3x1]{-0.8085,-0.7708,-1.0256},Raw=[2x1]{20.5606,-0.8093},time=1225719874.00646448135376,Speed=1.11708186092696,Pitch=0.00897341493535,Roll=0.04486707467677,PitchDot=0.05832719707980,RollDot=0.00116654394160
-62.359 ODOMETRY_POSE iPlatform Pose=[3x1]{4.6276,18.9343,-0.8086},Vel=[3x1]{-0.8085,-0.7708,-1.0263},Raw=[2x1]{20.5606,-0.8093},time=1225719874.0065,Speed=1.1171,Pitch=-0.0263,Roll=0.0375,PitchDot=0.0292,RollDot=0.0505
-62.362 LMS_LASER_2D_LEFT LMS1 ID=4082,time=1225719874.008531,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=79,Range=[181]{1.062,1.071,1.076,1.091,1.100,1.111,1.116,1.126,1.132,1.145,1.153,1.163,1.174,1.190,1.206,1.223,1.239,1.254,1.264,1.280,1.303,1.315,1.328,1.340,1.360,1.377,1.392,1.409,1.431,1.452,1.469,1.489,1.511,1.535,1.566,1.589,1.607,1.639,1.677,1.700,1.730,1.769,1.804,1.836,1.876,1.920,1.962,2.016,2.049,2.091,2.146,2.195,2.256,2.322,2.386,2.431,2.496,2.561,2.605,2.695,2.773,2.860,2.890,2.879,2.903,3.031,3.153,3.250,3.325,3.429,3.592,3.771,3.922,4.083,4.209,4.220,4.214,4.226,4.261,4.285,4.297,4.293,4.292,4.312,4.300,4.308,4.346,4.378,4.387,4.386,4.414,4.424,4.416,4.422,4.427,4.425,4.439,4.428,4.437,4.438,4.437,4.448,4.448,4.458,4.458,4.465,4.473,4.474,4.480,4.489,4.501,4.510,4.530,4.535,4.546,4.556,4.565,4.574,4.591,4.600,4.609,4.626,4.638,4.644,4.661,4.671,4.691,4.699,3.198,3.175,3.095,3.109,3.171,3.099,2.763,2.701,3.039,2.673,2.683,2.896,3.023,3.192,3.674,3.873,3.644,3.481,3.206,2.975,2.898,2.909,2.873,2.950,3.072,2.996,3.120,3.152,3.329,3.192,3.168,5.455,5.495,5.523,2.403,2.421,2.434,2.476,2.468,2.464,2.459,6.242,5.274,5.173,5.233,5.315,5.244,5.147,5.182,2.584,2.567,2.342,2.407},Reflectance=[181]{40.000,41.000,48.000,38.000,38.000,44.000,42.000,43.000,46.000,49.000,52.000,49.000,50.000,53.000,46.000,46.000,49.000,48.000,49.000,48.000,45.000,43.000,46.000,51.000,51.000,51.000,50.000,54.000,52.000,54.000,54.000,55.000,53.000,56.000,54.000,57.000,58.000,56.000,57.000,55.000,61.000,58.000,54.000,56.000,54.000,54.000,54.000,55.000,55.000,58.000,56.000,54.000,46.000,43.000,37.000,53.000,47.000,48.000,56.000,47.000,50.000,50.000,52.000,51.000,54.000,50.000,54.000,46.000,49.000,51.000,46.000,51.000,46.000,47.000,62.000,72.000,73.000,71.000,71.000,73.000,74.000,75.000,75.000,75.000,75.000,74.000,72.000,74.000,76.000,76.000,76.000,77.000,77.000,76.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,30.000,88.000,75.000,77.000,90.000,112.000,102.000,50.000,122.000,72.000,72.000,75.000,97.000,111.000,96.000,98.000,103.000,40.000,117.000,83.000,78.000,76.000,70.000,78.000,63.000,58.000,68.000,62.000,99.000,36.000,56.000,69.000,70.000,68.000,31.000,73.000,75.000,69.000,74.000,73.000,28.000,66.000,81.000,68.000,77.000,85.000,80.000,68.000,85.000,21.000,55.000,26.000,99.000}
-62.362 LMS_LASER_2D_RIGHT LMS2 ID=3954,time=1225719874.000691,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=43,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-6.000,-1.000,-6.000,-6.000,-6.000,-6.000,27.744,18.829,15.404,12.665,10.858,9.793,8.858,8.071,7.386,6.800,6.264,5.859,5.485,5.130,4.828,4.578,4.195,4.073,3.907,3.730,3.528,3.345,3.198,3.029,2.911,2.796,2.705,2.615,2.526,2.443,2.372,2.294,2.210,2.147,2.095,2.031,1.977,1.935,1.872,1.841,1.776,1.739,1.707,1.662,1.635,1.604,1.577,1.541,1.518,1.465,1.446,1.426,1.391,1.370,1.356,1.328,1.318,1.295,1.273,1.271,1.253,1.251,1.248,1.257,1.265,1.267,1.262,1.247,1.240,1.222,1.221,1.209,1.197,1.192,1.168,1.132,1.125,1.114,1.107,1.083,1.065,1.064,1.094,1.079,1.075,1.066,1.065,1.047,1.039,1.026,1.012,1.013,1.004},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,22.000,22.000,108.000,111.000,82.000,63.000,59.000,58.000,55.000,62.000,68.000,67.000,67.000,70.000,70.000,71.000,77.000,76.000,75.000,76.000,76.000,79.000,80.000,78.000,79.000,80.000,80.000,81.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,78.000,80.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,77.000,76.000,78.000,77.000,75.000,74.000,75.000,75.000,75.000,75.000,77.000,76.000,73.000,70.000,66.000,59.000,51.000,52.000,57.000,64.000,66.000,66.000,63.000,61.000,60.000,53.000,38.000,38.000,41.000,32.000,29.000,28.000,26.000,27.000,44.000,45.000,43.000,43.000,42.000,40.000,38.000,35.000,32.000,38.000,32.000}
-62.383 DESIRED_THRUST iJoystick 84.5393230995
-62.383 DESIRED_RUDDER iJoystick 3.09152500992
-62.375 LMS_LASER_2D_LEFT LMS1 ID=4083,time=1225719874.021868,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=80,Range=[181]{1.063,1.077,1.081,1.085,1.106,1.106,1.115,1.132,1.136,1.157,1.165,1.174,1.169,1.189,1.209,1.221,1.241,1.252,1.263,1.279,1.295,1.309,1.336,1.351,1.363,1.382,1.391,1.408,1.429,1.445,1.475,1.503,1.520,1.535,1.567,1.594,1.620,1.640,1.671,1.686,1.723,1.770,1.814,1.843,1.876,1.947,1.979,2.016,2.062,2.099,2.151,2.204,2.268,2.331,2.378,2.426,2.508,2.575,2.640,2.702,2.791,2.861,2.879,2.886,2.915,3.029,3.168,3.261,3.341,3.449,3.608,3.764,3.945,4.104,4.209,4.219,4.214,4.227,4.258,4.281,4.289,4.284,4.293,4.313,4.292,4.313,4.355,4.378,4.386,4.396,4.415,4.419,4.411,4.415,4.424,4.427,4.435,4.428,4.430,4.438,4.438,4.448,4.447,4.456,4.456,4.466,4.473,4.475,4.480,4.490,4.500,4.509,4.519,4.532,4.537,4.544,4.565,4.574,4.584,4.600,4.608,4.623,4.636,4.643,4.660,4.670,4.691,4.699,3.392,3.244,3.147,3.202,3.135,3.282,3.204,3.004,2.881,2.684,2.874,2.903,2.947,3.250,3.592,3.864,3.987,3.474,3.162,2.912,2.837,2.857,2.832,2.930,2.996,3.002,3.122,3.233,3.210,3.169,3.170,5.466,2.499,2.394,2.379,2.424,2.449,2.475,2.475,2.484,5.815,6.245,5.324,5.223,5.234,5.216,5.212,5.165,2.584,2.567,2.532,2.429,2.318},Reflectance=[181]{41.000,39.000,45.000,39.000,45.000,46.000,46.000,45.000,44.000,45.000,41.000,46.000,55.000,53.000,51.000,49.000,50.000,47.000,48.000,47.000,45.000,49.000,44.000,48.000,49.000,49.000,53.000,53.000,55.000,55.000,52.000,53.000,53.000,56.000,55.000,55.000,55.000,56.000,58.000,64.000,61.000,55.000,54.000,56.000,54.000,51.000,54.000,55.000,56.000,58.000,54.000,55.000,51.000,44.000,49.000,55.000,43.000,45.000,45.000,46.000,46.000,51.000,51.000,51.000,56.000,53.000,52.000,48.000,44.000,52.000,50.000,44.000,42.000,48.000,62.000,72.000,73.000,71.000,70.000,72.000,74.000,75.000,75.000,76.000,75.000,73.000,72.000,74.000,76.000,76.000,77.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,75.000,76.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,117.000,90.000,81.000,106.000,33.000,113.000,107.000,22.000,118.000,72.000,76.000,74.000,75.000,84.000,85.000,98.000,108.000,35.000,108.000,84.000,75.000,76.000,71.000,67.000,67.000,61.000,60.000,54.000,59.000,64.000,45.000,72.000,3.000,44.000,66.000,74.000,74.000,63.000,63.000,45.000,69.000,67.000,85.000,77.000,78.000,78.000,76.000,71.000,19.000,55.000,59.000,76.000,87.000}
-62.375 LMS_LASER_2D_RIGHT LMS2 ID=3955,time=1225719874.014037,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=44,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-6.000,-6.000,-6.000,-6.000,27.772,17.649,15.185,12.376,10.734,9.699,8.791,8.008,7.296,6.758,6.201,5.812,5.467,5.094,4.800,4.552,4.215,4.056,3.874,3.690,3.521,3.345,3.174,3.026,2.906,2.792,2.687,2.605,2.525,2.433,2.353,2.285,2.200,2.139,2.070,2.027,1.985,1.922,1.873,1.832,1.774,1.732,1.698,1.653,1.619,1.583,1.564,1.534,1.501,1.477,1.452,1.424,1.388,1.369,1.337,1.324,1.311,1.289,1.281,1.261,1.252,1.236,1.241,1.248,1.251,1.255,1.249,1.248,1.238,1.241,1.230,1.208,1.200,1.185,1.159,1.133,1.128,1.119,1.110,1.125,1.084,1.064,1.084,1.079,1.073,1.066,1.058,1.046,1.037,1.014,1.022,1.010,0.998},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,21.000,6.000,108.000,111.000,79.000,61.000,57.000,57.000,56.000,62.000,68.000,66.000,67.000,70.000,70.000,71.000,75.000,73.000,76.000,76.000,77.000,79.000,78.000,77.000,80.000,79.000,80.000,80.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,78.000,79.000,80.000,78.000,79.000,79.000,79.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,76.000,75.000,76.000,77.000,76.000,72.000,74.000,68.000,65.000,60.000,62.000,60.000,59.000,63.000,60.000,63.000,61.000,57.000,54.000,36.000,38.000,42.000,35.000,30.000,38.000,30.000,29.000,43.000,45.000,46.000,43.000,43.000,40.000,42.000,31.000,35.000,37.000,34.000}
-62.386 LMS_LASER_2D_RIGHT LMS2 ID=3956,time=1225719874.027380,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=45,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.792,17.795,14.920,12.293,10.680,9.627,8.754,7.963,7.279,6.741,6.190,5.776,5.415,5.068,4.765,4.535,4.247,4.044,3.874,3.687,3.512,3.312,3.146,3.025,2.894,2.786,2.679,2.604,2.506,2.432,2.354,2.283,2.207,2.139,2.070,2.025,1.977,1.924,1.882,1.829,1.774,1.739,1.696,1.662,1.621,1.579,1.557,1.536,1.507,1.479,1.450,1.418,1.403,1.374,1.333,1.323,1.306,1.285,1.271,1.251,1.245,1.235,1.236,1.241,1.249,1.264,1.266,1.268,1.240,1.235,1.221,1.205,1.196,1.193,1.167,1.133,1.126,1.128,1.122,1.118,1.099,1.061,1.061,1.076,1.068,1.069,1.065,1.045,1.032,1.034,1.019,0.997,0.991},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,17.000,72.000,113.000,106.000,76.000,62.000,57.000,58.000,56.000,63.000,66.000,67.000,67.000,70.000,71.000,72.000,73.000,74.000,76.000,76.000,77.000,77.000,78.000,77.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,80.000,79.000,79.000,79.000,78.000,79.000,78.000,79.000,78.000,72.000,75.000,79.000,78.000,78.000,77.000,78.000,78.000,75.000,74.000,76.000,77.000,75.000,73.000,70.000,62.000,71.000,73.000,68.000,55.000,50.000,48.000,56.000,66.000,61.000,63.000,65.000,59.000,58.000,43.000,38.000,41.000,37.000,32.000,43.000,36.000,25.000,29.000,47.000,44.000,44.000,42.000,40.000,46.000,43.000,37.000,29.000,32.000}
-62.395 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.6600,18.9652,-0.8091},Vel=[3x1]{-0.8063,-0.7690,3.4615},Raw=[2x1]{20.6054,-0.8091},time=1225719874.04235148429871,Speed=1.11416138547356,Pitch=0.00897341493535,Roll=0.04711042841061,PitchDot=0.02243353733839,RollDot=0.00060570550814
-62.395 ODOMETRY_POSE iPlatform Pose=[3x1]{4.6600,18.9652,-0.8083},Vel=[3x1]{-0.8063,-0.7690,-2.8216},Raw=[2x1]{20.6054,-0.8091},time=1225719874.0424,Speed=1.1142,Pitch=-0.0279,Roll=0.0390,PitchDot=-0.0215,RollDot=0.0065
-62.395 VEHICLE_GEOMETRY iPlatform Name=LISA, Sensor_0=LMS_LASER_2D, Pose3D_0=[4x1]{0.0000,0.3500,0.0000,0.0000},SHAPE_2D=[2x8]{0.3300,0.3300,0.2100,0.2100,-0.2100,-0.2100,-0.3300,-0.3300,-0.4100,0.4100,0.4100,0.5700,0.5700,0.4100,0.4100,-0.4100,}
-62.398 LMS_LASER_2D_RIGHT LMS2 ID=3957,time=1225719874.040723,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=46,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.965,17.742,14.711,12.245,10.641,9.601,8.735,7.911,7.246,6.713,6.181,5.776,5.398,5.050,4.765,4.535,4.256,4.046,3.869,3.687,3.506,3.319,3.155,3.029,2.877,2.782,2.673,2.596,2.488,2.434,2.356,2.285,2.200,2.130,2.070,2.017,1.961,1.918,1.873,1.829,1.787,1.735,1.692,1.659,1.624,1.589,1.562,1.536,1.508,1.479,1.444,1.420,1.411,1.369,1.342,1.315,1.306,1.289,1.271,1.253,1.250,1.248,1.240,1.256,1.260,1.266,1.270,1.257,1.232,1.214,1.200,1.198,1.199,1.188,1.162,1.130,1.127,1.134,1.125,1.114,1.106,1.052,1.041,1.078,1.068,1.068,1.059,1.044,1.042,1.021,1.019,1.010,1.004},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,13.000,84.000,118.000,103.000,75.000,62.000,57.000,58.000,57.000,62.000,66.000,66.000,67.000,70.000,70.000,71.000,73.000,74.000,77.000,75.000,78.000,76.000,78.000,78.000,79.000,81.000,81.000,80.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,79.000,77.000,78.000,77.000,78.000,79.000,77.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,74.000,73.000,74.000,77.000,72.000,73.000,73.000,68.000,66.000,67.000,63.000,56.000,51.000,45.000,59.000,66.000,66.000,72.000,69.000,60.000,52.000,36.000,40.000,43.000,41.000,36.000,53.000,40.000,26.000,28.000,45.000,44.000,44.000,41.000,37.000,39.000,32.000,35.000,37.000,40.000}
-62.407 DESIRED_THRUST iJoystick 83.5077974792
-62.407 DESIRED_RUDDER iJoystick 3.09152500992
-61.590 CAMERA_FILE_WRITE iCameraLadybug time=1225719873.237,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.237-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.237-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.237-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.237-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.237-4.jpg
-62.398 LMS_LASER_2D_LEFT LMS1 ID=4084,time=1225719874.035215,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=81,Range=[181]{1.065,1.069,1.077,1.088,1.103,1.111,1.124,1.125,1.135,1.147,1.166,1.182,1.179,1.202,1.212,1.226,1.238,1.254,1.269,1.278,1.298,1.315,1.329,1.344,1.375,1.383,1.391,1.425,1.433,1.461,1.478,1.497,1.525,1.549,1.575,1.597,1.620,1.653,1.681,1.677,1.721,1.776,1.814,1.843,1.884,1.929,1.981,2.012,2.053,2.106,2.151,2.197,2.261,2.312,2.381,2.431,2.513,2.564,2.649,2.710,2.789,2.862,2.884,2.877,2.910,3.040,3.171,3.273,3.344,3.465,3.626,3.776,3.963,4.111,4.191,4.212,4.212,4.217,4.259,4.278,4.289,4.284,4.292,4.311,4.295,4.298,4.342,4.382,4.376,4.397,4.410,4.411,4.403,4.418,4.418,4.419,4.431,4.429,4.428,4.439,4.439,4.444,4.448,4.448,4.458,4.457,4.464,4.473,4.481,4.491,4.491,4.498,4.514,4.525,4.535,4.548,4.556,4.573,4.583,4.594,4.608,4.623,4.635,4.644,4.668,4.671,4.691,4.699,3.776,3.450,3.432,4.767,3.373,3.197,3.153,2.994,2.851,2.885,2.887,2.912,3.080,3.605,3.584,3.643,3.672,3.560,3.277,2.861,2.812,2.795,2.816,2.901,3.014,3.055,3.167,3.185,3.184,3.162,5.432,5.455,5.493,2.395,2.388,2.417,2.457,2.474,2.450,5.638,5.819,6.260,5.451,5.219,5.173,5.158,5.169,5.175,2.557,2.535,2.515,2.438,2.330},Reflectance=[181]{42.000,44.000,44.000,41.000,40.000,44.000,42.000,47.000,48.000,46.000,46.000,45.000,49.000,43.000,48.000,51.000,52.000,48.000,47.000,47.000,48.000,48.000,50.000,49.000,46.000,54.000,53.000,54.000,53.000,54.000,54.000,55.000,55.000,55.000,55.000,56.000,55.000,54.000,59.000,65.000,60.000,53.000,54.000,55.000,57.000,54.000,54.000,57.000,60.000,58.000,54.000,55.000,56.000,55.000,54.000,49.000,47.000,53.000,45.000,46.000,49.000,48.000,53.000,54.000,54.000,47.000,46.000,49.000,46.000,45.000,45.000,43.000,45.000,48.000,64.000,72.000,72.000,71.000,71.000,71.000,74.000,75.000,75.000,75.000,74.000,72.000,71.000,72.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,79.000,107.000,82.000,106.000,78.000,116.000,74.000,89.000,50.000,84.000,76.000,75.000,74.000,96.000,89.000,83.000,93.000,109.000,109.000,74.000,79.000,75.000,73.000,71.000,66.000,69.000,65.000,60.000,41.000,48.000,35.000,72.000,71.000,70.000,40.000,61.000,72.000,62.000,28.000,25.000,63.000,67.000,65.000,88.000,76.000,76.000,65.000,67.000,71.000,29.000,61.000,73.000,83.000,79.000}
-62.410 LMS_LASER_2D_LEFT LMS1 ID=4085,time=1225719874.048561,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=82,Range=[181]{1.073,1.072,1.084,1.086,1.107,1.116,1.127,1.130,1.147,1.153,1.163,1.172,1.191,1.202,1.219,1.231,1.241,1.262,1.278,1.282,1.300,1.315,1.336,1.346,1.367,1.388,1.399,1.425,1.441,1.451,1.477,1.495,1.522,1.549,1.573,1.607,1.623,1.652,1.677,1.677,1.725,1.775,1.808,1.841,1.892,1.936,1.991,2.009,2.054,2.117,2.152,2.204,2.264,2.312,2.381,2.420,2.519,2.558,2.649,2.714,2.795,2.863,2.879,2.872,2.900,3.050,3.154,3.268,3.328,3.455,3.617,3.781,3.949,4.090,4.200,4.205,4.205,4.215,4.261,4.284,4.280,4.284,4.283,4.300,4.286,4.309,4.342,4.371,4.374,4.388,4.402,4.403,4.404,4.410,4.412,4.420,4.432,4.419,4.429,4.430,4.439,4.438,4.437,4.448,4.448,4.456,4.464,4.473,4.473,4.481,4.491,4.498,4.511,4.525,4.537,4.548,4.556,4.564,4.583,4.591,4.599,4.620,4.627,4.646,4.654,4.669,4.681,3.937,3.709,3.545,3.637,3.552,3.412,3.266,3.180,3.110,2.979,2.904,2.916,3.059,3.754,3.805,3.500,3.482,3.644,3.091,2.852,2.839,2.811,2.802,2.833,2.909,3.074,3.088,3.152,3.194,5.360,5.397,5.421,5.458,5.493,5.512,2.403,2.435,2.466,2.448,2.450,5.646,5.806,6.297,5.325,5.134,5.125,5.142,5.150,5.226,2.544,2.515,2.510,2.399,2.343},Reflectance=[181]{41.000,37.000,43.000,40.000,42.000,42.000,43.000,46.000,41.000,44.000,44.000,46.000,45.000,48.000,48.000,49.000,50.000,43.000,42.000,49.000,44.000,48.000,49.000,53.000,51.000,48.000,53.000,54.000,53.000,53.000,53.000,54.000,54.000,55.000,54.000,54.000,57.000,58.000,61.000,64.000,59.000,57.000,56.000,55.000,57.000,54.000,51.000,56.000,57.000,54.000,55.000,55.000,57.000,55.000,54.000,56.000,54.000,55.000,45.000,48.000,48.000,48.000,51.000,55.000,57.000,48.000,46.000,47.000,46.000,45.000,50.000,44.000,50.000,46.000,63.000,72.000,72.000,70.000,71.000,73.000,74.000,75.000,75.000,75.000,73.000,72.000,71.000,72.000,75.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,76.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,78.000,78.000,79.000,103.000,103.000,74.000,96.000,21.000,119.000,89.000,90.000,90.000,92.000,77.000,75.000,100.000,103.000,74.000,85.000,88.000,110.000,113.000,77.000,76.000,75.000,72.000,71.000,63.000,74.000,69.000,46.000,27.000,75.000,75.000,72.000,70.000,70.000,68.000,34.000,55.000,64.000,69.000,54.000,62.000,62.000,63.000,89.000,77.000,77.000,69.000,67.000,80.000,39.000,73.000,74.000,69.000,80.000}
-62.410 LMS_LASER_2D_RIGHT LMS2 ID=3958,time=1225719874.054063,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=47,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,27.941,17.682,14.601,12.181,10.614,9.571,8.726,7.893,7.231,6.687,6.145,5.758,5.406,5.076,4.782,4.526,4.247,4.049,3.844,3.668,3.500,3.340,3.163,3.022,2.890,2.782,2.689,2.578,2.506,2.425,2.349,2.275,2.200,2.122,2.071,2.019,1.961,1.918,1.875,1.830,1.788,1.731,1.689,1.647,1.624,1.587,1.554,1.527,1.499,1.471,1.448,1.424,1.406,1.359,1.341,1.324,1.308,1.295,1.279,1.260,1.244,1.242,1.241,1.254,1.265,1.264,1.277,1.250,1.239,1.214,1.200,1.205,1.199,1.197,1.162,1.137,1.130,1.127,1.125,1.103,1.102,1.057,1.067,1.084,1.065,1.066,1.054,1.046,1.043,1.014,1.027,1.018,1.014},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,19.000,88.000,118.000,101.000,75.000,61.000,57.000,58.000,58.000,63.000,66.000,67.000,67.000,70.000,70.000,72.000,73.000,74.000,77.000,75.000,76.000,77.000,78.000,78.000,80.000,81.000,81.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,77.000,77.000,74.000,75.000,79.000,78.000,79.000,79.000,78.000,78.000,76.000,77.000,77.000,71.000,76.000,76.000,74.000,71.000,72.000,70.000,74.000,71.000,68.000,62.000,54.000,51.000,44.000,60.000,65.000,66.000,72.000,66.000,60.000,48.000,36.000,42.000,45.000,44.000,46.000,59.000,44.000,27.000,31.000,43.000,42.000,43.000,40.000,40.000,39.000,31.000,37.000,39.000,38.000}
-62.423 LMS_LASER_2D_LEFT LMS1 ID=4086,time=1225719874.061906,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=83,Range=[181]{1.068,1.080,1.090,1.092,1.107,1.114,1.124,1.131,1.149,1.150,1.170,1.181,1.194,1.212,1.222,1.225,1.245,1.258,1.264,1.284,1.294,1.316,1.334,1.346,1.355,1.374,1.392,1.418,1.443,1.452,1.471,1.487,1.530,1.548,1.574,1.598,1.620,1.647,1.674,1.703,1.743,1.778,1.821,1.848,1.894,1.937,1.979,2.015,2.060,2.127,2.178,2.221,2.267,2.330,2.384,2.419,2.500,2.540,2.648,2.719,2.792,2.863,2.868,2.864,2.896,3.040,3.146,3.257,3.329,3.440,3.613,3.812,3.956,4.123,4.191,4.203,4.205,4.219,4.255,4.275,4.281,4.274,4.280,4.298,4.278,4.299,4.344,4.369,4.375,4.386,4.403,4.403,4.406,4.415,4.412,4.418,4.425,4.419,4.419,4.429,4.436,4.430,4.439,4.439,4.447,4.446,4.453,4.464,4.473,4.481,4.490,4.500,4.514,4.523,4.528,4.537,4.545,4.565,4.574,4.584,4.599,4.611,4.627,4.638,4.649,4.667,4.680,3.819,3.687,3.570,3.578,3.770,4.774,3.213,3.208,3.034,2.903,2.974,2.956,3.092,3.729,3.689,3.451,3.439,3.565,3.052,2.929,2.852,2.842,2.821,2.864,2.993,3.178,3.164,3.161,3.206,5.351,5.387,5.417,5.448,5.480,2.555,2.437,2.496,2.468,2.448,2.487,5.638,5.780,6.359,5.211,5.093,5.214,5.208,5.154,5.252,2.518,2.510,2.496,2.394,2.346},Reflectance=[181]{39.000,41.000,41.000,43.000,41.000,45.000,41.000,46.000,45.000,47.000,44.000,45.000,43.000,44.000,44.000,46.000,48.000,50.000,49.000,46.000,50.000,48.000,48.000,53.000,53.000,54.000,54.000,54.000,54.000,54.000,55.000,54.000,54.000,54.000,54.000,54.000,55.000,55.000,60.000,61.000,59.000,54.000,54.000,54.000,54.000,54.000,54.000,54.000,55.000,51.000,51.000,54.000,54.000,55.000,55.000,55.000,57.000,55.000,42.000,45.000,47.000,48.000,50.000,56.000,59.000,51.000,47.000,46.000,46.000,48.000,42.000,46.000,50.000,49.000,62.000,72.000,72.000,72.000,72.000,73.000,75.000,75.000,74.000,75.000,74.000,72.000,72.000,74.000,76.000,76.000,78.000,79.000,79.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,76.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,77.000,77.000,78.000,104.000,92.000,74.000,79.000,108.000,78.000,37.000,110.000,92.000,76.000,93.000,48.000,47.000,105.000,109.000,100.000,85.000,113.000,115.000,99.000,77.000,76.000,75.000,68.000,65.000,99.000,59.000,58.000,43.000,75.000,75.000,71.000,69.000,71.000,2.000,30.000,55.000,74.000,61.000,9.000,61.000,57.000,64.000,80.000,72.000,83.000,83.000,68.000,83.000,63.000,74.000,75.000,73.000,79.000}
-62.423 LMS_LASER_2D_RIGHT LMS2 ID=3959,time=1225719874.067403,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=48,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.722,17.406,14.719,12.238,10.649,9.601,8.735,7.911,7.240,6.705,6.154,5.785,5.407,5.102,4.791,4.527,4.239,4.049,3.860,3.665,3.512,3.349,3.157,3.024,2.890,2.796,2.697,2.604,2.524,2.423,2.356,2.274,2.198,2.130,2.071,2.019,1.969,1.927,1.873,1.832,1.792,1.741,1.688,1.647,1.623,1.587,1.553,1.527,1.493,1.472,1.450,1.432,1.396,1.360,1.347,1.337,1.323,1.311,1.280,1.262,1.244,1.244,1.243,1.247,1.263,1.270,1.274,1.261,1.235,1.230,1.219,1.213,1.200,1.195,1.164,1.134,1.122,1.123,1.119,1.106,1.103,1.051,1.062,1.079,1.074,1.067,1.058,1.047,1.041,1.020,1.023,1.018,1.006},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,7.000,27.000,118.000,104.000,75.000,62.000,57.000,58.000,58.000,63.000,66.000,66.000,67.000,68.000,70.000,72.000,73.000,74.000,76.000,74.000,77.000,77.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,78.000,74.000,72.000,75.000,78.000,78.000,79.000,79.000,79.000,78.000,77.000,77.000,73.000,72.000,78.000,78.000,72.000,67.000,73.000,73.000,73.000,72.000,71.000,64.000,53.000,49.000,41.000,53.000,61.000,59.000,57.000,55.000,57.000,47.000,37.000,41.000,45.000,49.000,55.000,57.000,37.000,26.000,30.000,40.000,43.000,43.000,41.000,38.000,36.000,34.000,34.000,37.000,38.000}
-62.431 DESIRED_THRUST iJoystick 83.5077974792
-62.431 DESIRED_RUDDER iJoystick 3.09152500992
-62.431 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.6840,18.9880,-0.8107},Vel=[3x1]{-0.7980,-0.7586,9.3590},Raw=[2x1]{20.6385,-0.8107},time=1225719874.07843852043152,Speed=1.10101924593324,Pitch=0.00897341493535,Roll=0.04711042841061,PitchDot=0.00673006120152,RollDot=0.00020190183605
-62.431 ODOMETRY_POSE iPlatform Pose=[3x1]{4.6840,18.9880,-0.8099},Vel=[3x1]{-0.7980,-0.7586,3.0758},Raw=[2x1]{20.6385,-0.8107},time=1225719874.0784,Speed=1.1010,Pitch=-0.0280,Roll=0.0390,PitchDot=-0.0067,RollDot=-0.0006
-62.455 DESIRED_THRUST iJoystick 84.5393230995
-62.455 DESIRED_RUDDER iJoystick 4.12305063021
-62.423 LMS_LASER_2D_LEFT LMS1 ID=4087,time=1225719874.075238,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=84,Range=[181]{1.064,1.074,1.080,1.092,1.105,1.116,1.124,1.131,1.141,1.151,1.174,1.171,1.191,1.208,1.223,1.228,1.241,1.256,1.266,1.286,1.300,1.312,1.335,1.347,1.356,1.383,1.401,1.415,1.442,1.459,1.472,1.489,1.524,1.561,1.573,1.596,1.616,1.639,1.671,1.712,1.741,1.776,1.813,1.861,1.895,1.937,1.989,2.031,2.068,2.122,2.178,2.212,2.277,2.318,2.373,2.416,2.515,2.542,2.652,2.721,2.794,2.864,2.870,2.855,2.900,3.054,3.155,3.234,3.337,3.449,3.609,3.800,3.961,4.112,4.200,4.198,4.196,4.207,4.247,4.268,4.272,4.275,4.280,4.297,4.275,4.300,4.334,4.373,4.374,4.378,4.399,4.403,4.403,4.395,4.403,4.402,4.417,4.410,4.421,4.419,4.428,4.429,4.437,4.438,4.439,4.446,4.444,4.462,4.472,4.474,4.483,4.489,4.496,4.517,4.527,4.535,4.547,4.553,4.574,4.581,4.591,4.606,4.619,4.635,4.643,4.660,4.671,4.691,3.731,3.568,3.577,3.740,3.752,3.463,3.112,2.931,2.848,2.941,3.014,3.166,3.702,4.945,3.491,3.366,3.498,3.608,3.001,2.959,2.900,2.820,2.872,3.180,3.196,3.188,3.155,3.183,5.352,5.387,5.416,5.447,2.503,2.510,2.448,2.453,2.465,2.539,2.422,5.632,5.732,6.402,5.321,5.222,5.309,5.214,5.143,5.192,2.538,2.509,2.509,2.459,2.396},Reflectance=[181]{45.000,42.000,41.000,43.000,40.000,42.000,45.000,49.000,47.000,43.000,42.000,33.000,45.000,46.000,46.000,48.000,50.000,44.000,46.000,46.000,49.000,54.000,52.000,54.000,54.000,54.000,54.000,50.000,53.000,53.000,55.000,55.000,55.000,52.000,54.000,56.000,58.000,56.000,54.000,56.000,58.000,53.000,54.000,55.000,55.000,54.000,54.000,54.000,55.000,52.000,55.000,54.000,55.000,54.000,54.000,58.000,55.000,56.000,48.000,45.000,48.000,49.000,51.000,56.000,57.000,46.000,47.000,47.000,45.000,48.000,43.000,49.000,59.000,56.000,63.000,73.000,72.000,71.000,72.000,73.000,75.000,75.000,74.000,74.000,73.000,72.000,72.000,75.000,75.000,74.000,77.000,78.000,79.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,76.000,77.000,78.000,77.000,78.000,77.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,79.000,106.000,76.000,76.000,107.000,108.000,90.000,87.000,93.000,76.000,94.000,119.000,119.000,113.000,78.000,112.000,72.000,103.000,103.000,109.000,103.000,80.000,70.000,68.000,101.000,17.000,58.000,47.000,51.000,76.000,75.000,73.000,72.000,26.000,50.000,65.000,68.000,69.000,42.000,16.000,58.000,59.000,64.000,96.000,82.000,93.000,83.000,67.000,85.000,31.000,63.000,62.000,84.000,82.000}
-62.434 LMS_LASER_2D_RIGHT LMS2 ID=3960,time=1225719874.080741,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=49,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.870,14.799,12.318,10.681,9.638,8.763,7.954,7.289,6.741,6.200,5.803,5.423,5.111,4.782,4.544,4.239,4.056,3.877,3.677,3.530,3.352,3.147,3.050,2.912,2.810,2.707,2.605,2.507,2.425,2.364,2.285,2.210,2.130,2.078,2.011,1.962,1.929,1.892,1.839,1.793,1.741,1.681,1.658,1.616,1.589,1.553,1.530,1.502,1.475,1.455,1.436,1.404,1.366,1.345,1.337,1.308,1.297,1.287,1.262,1.246,1.244,1.251,1.241,1.253,1.274,1.277,1.279,1.242,1.227,1.220,1.218,1.200,1.199,1.172,1.137,1.128,1.121,1.111,1.105,1.107,1.086,1.085,1.084,1.071,1.057,1.059,1.048,1.043,1.024,0.994,1.008,1.005},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,63.000,116.000,106.000,77.000,62.000,57.000,58.000,57.000,63.000,66.000,66.000,67.000,68.000,71.000,71.000,72.000,74.000,76.000,75.000,77.000,78.000,78.000,79.000,79.000,79.000,81.000,80.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,79.000,74.000,74.000,78.000,79.000,79.000,79.000,80.000,79.000,79.000,78.000,78.000,72.000,68.000,77.000,78.000,74.000,74.000,69.000,73.000,74.000,74.000,69.000,68.000,61.000,47.000,44.000,42.000,60.000,61.000,58.000,57.000,57.000,49.000,37.000,40.000,44.000,52.000,59.000,56.000,36.000,32.000,41.000,43.000,42.000,41.000,41.000,38.000,39.000,34.000,29.000,33.000,32.000}
-62.446 LMS_LASER_2D_LEFT LMS1 ID=4088,time=1225719874.088580,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=85,Range=[181]{1.064,1.077,1.086,1.094,1.101,1.118,1.119,1.136,1.147,1.153,1.171,1.183,1.184,1.200,1.216,1.225,1.241,1.254,1.266,1.276,1.291,1.321,1.334,1.337,1.360,1.381,1.400,1.408,1.433,1.461,1.477,1.488,1.521,1.556,1.573,1.599,1.612,1.639,1.679,1.709,1.741,1.773,1.804,1.860,1.894,1.951,1.971,2.027,2.074,2.120,2.169,2.213,2.273,2.319,2.379,2.428,2.503,2.559,2.647,2.694,2.794,2.861,2.867,2.853,2.892,3.045,3.151,3.239,3.322,3.434,3.595,3.780,3.951,4.089,4.190,4.196,4.186,4.208,4.245,4.268,4.272,4.267,4.272,4.288,4.272,4.281,4.332,4.361,4.373,4.374,4.399,4.394,4.395,4.394,4.406,4.403,4.399,4.403,4.410,4.418,4.420,4.420,4.429,4.428,4.439,4.436,4.446,4.458,4.462,4.475,4.481,4.492,4.496,4.507,4.519,4.529,4.539,4.547,4.564,4.574,4.593,4.600,4.611,4.627,4.642,4.651,4.671,4.681,3.636,3.558,3.567,3.666,3.608,3.168,2.884,2.830,2.848,2.885,3.040,3.035,4.919,4.944,3.381,3.447,3.451,3.544,3.462,2.981,2.908,2.797,2.832,3.019,3.199,3.200,3.114,3.174,5.342,5.384,5.411,2.525,2.496,2.499,2.451,2.449,2.449,2.474,2.400,2.397,5.708,6.359,6.480,5.271,5.320,5.248,5.156,5.156,5.086,5.040,2.517,2.428,2.348},Reflectance=[181]{41.000,39.000,44.000,44.000,43.000,43.000,43.000,39.000,41.000,44.000,40.000,38.000,47.000,47.000,46.000,50.000,50.000,43.000,53.000,54.000,52.000,46.000,52.000,53.000,51.000,53.000,53.000,53.000,53.000,54.000,53.000,55.000,54.000,54.000,54.000,54.000,60.000,56.000,53.000,55.000,54.000,56.000,54.000,54.000,54.000,52.000,54.000,52.000,54.000,51.000,55.000,55.000,53.000,55.000,53.000,56.000,50.000,51.000,50.000,54.000,44.000,51.000,50.000,55.000,57.000,49.000,49.000,45.000,43.000,49.000,44.000,48.000,59.000,58.000,56.000,72.000,72.000,71.000,72.000,73.000,75.000,75.000,75.000,74.000,72.000,72.000,71.000,74.000,75.000,73.000,77.000,78.000,79.000,78.000,79.000,78.000,77.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,95.000,75.000,75.000,88.000,94.000,79.000,80.000,75.000,76.000,80.000,105.000,49.000,78.000,78.000,33.000,85.000,86.000,109.000,110.000,115.000,80.000,69.000,65.000,53.000,45.000,55.000,34.000,51.000,75.000,75.000,74.000,14.000,55.000,44.000,42.000,71.000,74.000,57.000,59.000,34.000,59.000,64.000,61.000,84.000,94.000,82.000,80.000,80.000,88.000,32.000,28.000,68.000,43.000}
-62.467 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.7163,19.0186,-0.8147},Vel=[3x1]{-0.8106,-0.7644,14.4872},Raw=[2x1]{20.6831,-0.8147},time=1225719874.11434245109558,Speed=1.11416138547356,Pitch=0.00897341493535,Roll=0.04711042841061,PitchDot=-0.00897341493535,RollDot=-0.00080760734418
-62.467 ODOMETRY_POSE iPlatform Pose=[3x1]{4.7163,19.0186,-0.8139},Vel=[3x1]{-0.8106,-0.7644,1.9208},Raw=[2x1]{20.6831,-0.8147},time=1225719874.1143,Speed=1.1142,Pitch=-0.0281,Roll=0.0389,PitchDot=0.0023,RollDot=0.0087
-62.479 DESIRED_THRUST iJoystick 84.5393230995
-62.479 DESIRED_RUDDER iJoystick 4.12305063021
-62.447 LMS_LASER_2D_LEFT LMS1 ID=4089,time=1225719874.101909,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=86,Range=[181]{1.063,1.073,1.079,1.089,1.103,1.106,1.118,1.124,1.135,1.161,1.169,1.182,1.198,1.195,1.207,1.225,1.233,1.246,1.250,1.260,1.287,1.315,1.325,1.342,1.357,1.390,1.391,1.400,1.425,1.445,1.470,1.487,1.519,1.556,1.578,1.598,1.613,1.639,1.673,1.704,1.737,1.777,1.814,1.849,1.893,1.947,1.968,2.006,2.063,2.121,2.161,2.205,2.250,2.312,2.381,2.431,2.496,2.567,2.631,2.702,2.789,2.859,2.859,2.844,2.883,3.035,3.141,3.191,3.320,3.413,3.574,3.735,3.974,4.098,4.175,4.184,4.187,4.191,4.229,4.255,4.263,4.267,4.263,4.284,4.275,4.271,4.317,4.361,4.364,4.365,4.397,4.391,4.394,4.394,4.394,4.394,4.394,4.403,4.401,4.412,4.410,4.419,4.420,4.429,4.430,4.439,4.438,4.445,4.454,4.463,4.474,4.483,4.489,4.501,4.508,4.519,4.539,4.549,4.556,4.575,4.583,4.593,4.601,4.618,4.633,4.641,3.756,3.740,3.694,3.588,3.588,3.196,3.096,2.958,2.890,2.853,2.942,2.916,3.012,3.244,4.126,2.906,2.815,3.135,3.465,3.526,2.980,2.808,2.834,2.775,2.832,3.013,3.075,3.150,3.110,3.171,5.334,5.369,5.391,5.437,5.471,5.507,2.573,2.521,2.480,2.482,2.383,2.360,5.669,6.037,6.522,5.202,5.127,5.279,5.183,5.235,4.986,4.973,2.307,2.227,2.206},Reflectance=[181]{46.000,42.000,46.000,46.000,44.000,46.000,43.000,46.000,48.000,43.000,39.000,45.000,41.000,52.000,50.000,45.000,50.000,48.000,54.000,54.000,51.000,43.000,52.000,51.000,50.000,53.000,53.000,53.000,54.000,55.000,54.000,54.000,53.000,54.000,52.000,54.000,56.000,56.000,55.000,56.000,56.000,54.000,54.000,54.000,54.000,51.000,56.000,54.000,53.000,49.000,51.000,55.000,55.000,51.000,46.000,50.000,47.000,47.000,47.000,45.000,45.000,50.000,50.000,55.000,57.000,52.000,49.000,55.000,45.000,44.000,46.000,51.000,54.000,53.000,57.000,72.000,72.000,71.000,70.000,72.000,74.000,75.000,74.000,75.000,73.000,72.000,72.000,74.000,75.000,73.000,77.000,78.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,105.000,106.000,105.000,84.000,84.000,89.000,78.000,75.000,78.000,77.000,110.000,52.000,95.000,121.000,103.000,28.000,36.000,100.000,85.000,96.000,114.000,72.000,74.000,67.000,65.000,43.000,28.000,60.000,36.000,54.000,76.000,75.000,74.000,74.000,74.000,71.000,30.000,55.000,48.000,49.000,55.000,18.000,60.000,72.000,60.000,22.000,29.000,83.000,85.000,85.000,54.000,43.000,49.000,65.000,43.000}
-62.447 LMS_LASER_2D_RIGHT LMS2 ID=3961,time=1225719874.094078,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=50,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.792,18.667,15.180,12.519,10.772,9.708,8.819,8.016,7.345,6.792,6.235,5.850,5.459,5.155,4.828,4.571,4.274,4.073,3.905,3.701,3.544,3.375,3.173,3.042,2.906,2.821,2.716,2.604,2.531,2.441,2.373,2.294,2.210,2.147,2.084,2.019,1.961,1.930,1.901,1.847,1.803,1.726,1.679,1.653,1.626,1.590,1.563,1.527,1.501,1.484,1.454,1.432,1.421,1.367,1.353,1.333,1.302,1.303,1.288,1.271,1.250,1.239,1.241,1.249,1.247,1.277,1.277,1.273,1.263,1.248,1.221,1.223,1.196,1.197,1.175,1.137,1.134,1.133,1.114,1.114,1.065,1.076,1.086,1.087,1.071,1.068,1.061,1.052,1.043,1.027,1.030,1.003,0.979},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,17.000,33.000,113.000,107.000,80.000,61.000,57.000,57.000,56.000,62.000,66.000,66.000,67.000,68.000,70.000,71.000,72.000,73.000,77.000,75.000,78.000,80.000,78.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,79.000,80.000,80.000,81.000,80.000,79.000,79.000,77.000,76.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,69.000,68.000,77.000,77.000,75.000,76.000,72.000,72.000,75.000,75.000,69.000,67.000,63.000,48.000,44.000,41.000,46.000,51.000,55.000,52.000,59.000,52.000,49.000,40.000,43.000,49.000,56.000,53.000,26.000,30.000,42.000,44.000,45.000,44.000,45.000,42.000,36.000,35.000,35.000,31.000,29.000}
-62.470 LMS_LASER_2D_LEFT LMS1 ID=4090,time=1225719874.115248,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=87,Range=[181]{1.068,1.069,1.084,1.094,1.090,1.111,1.124,1.129,1.140,1.149,1.164,1.177,1.188,1.192,1.212,1.218,1.234,1.240,1.242,1.271,1.289,1.309,1.330,1.340,1.353,1.379,1.391,1.415,1.424,1.452,1.461,1.474,1.502,1.554,1.565,1.590,1.618,1.639,1.664,1.703,1.731,1.778,1.814,1.840,1.884,1.929,1.964,1.995,2.047,2.107,2.143,2.197,2.249,2.304,2.362,2.433,2.502,2.555,2.616,2.698,2.780,2.838,2.864,2.846,2.875,3.021,3.123,3.175,3.260,3.394,3.541,3.716,3.938,4.079,4.174,4.181,4.187,4.187,4.220,4.248,4.264,4.259,4.258,4.274,4.269,4.271,4.300,4.345,4.365,4.355,4.387,4.382,4.385,4.386,4.385,4.386,4.394,4.394,4.403,4.401,4.411,4.421,4.419,4.421,4.421,4.428,4.430,4.437,4.452,4.458,4.469,4.481,4.480,4.490,4.510,4.519,4.528,4.536,4.548,4.556,4.573,4.592,4.594,4.610,4.625,4.640,3.727,3.542,3.595,3.664,3.646,3.178,2.978,2.928,2.913,3.013,4.208,2.986,2.942,2.992,2.825,2.841,2.849,2.836,3.482,3.633,2.943,2.813,2.811,2.788,2.872,3.030,3.115,3.223,3.300,3.194,5.319,5.348,5.383,5.423,5.458,5.488,2.574,2.523,5.567,2.439,2.393,5.616,5.628,5.917,6.561,6.633,5.110,5.330,5.223,5.302,2.110,2.118,2.108,2.141,2.166},Reflectance=[181]{43.000,44.000,43.000,44.000,50.000,44.000,45.000,44.000,45.000,46.000,46.000,43.000,52.000,51.000,44.000,47.000,47.000,53.000,54.000,48.000,43.000,44.000,45.000,47.000,49.000,52.000,53.000,50.000,53.000,54.000,58.000,60.000,57.000,53.000,54.000,53.000,55.000,56.000,55.000,56.000,53.000,54.000,54.000,54.000,53.000,54.000,55.000,56.000,54.000,54.000,55.000,55.000,54.000,51.000,47.000,42.000,45.000,46.000,48.000,44.000,46.000,55.000,52.000,55.000,57.000,50.000,49.000,55.000,51.000,48.000,48.000,54.000,57.000,41.000,57.000,71.000,72.000,70.000,72.000,72.000,75.000,76.000,75.000,75.000,74.000,72.000,70.000,72.000,75.000,72.000,76.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,76.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,77.000,103.000,78.000,101.000,103.000,96.000,107.000,79.000,76.000,77.000,96.000,97.000,122.000,95.000,117.000,54.000,49.000,98.000,77.000,83.000,109.000,111.000,73.000,75.000,69.000,38.000,50.000,31.000,57.000,35.000,27.000,76.000,75.000,74.000,72.000,72.000,68.000,41.000,47.000,66.000,29.000,32.000,70.000,60.000,67.000,58.000,60.000,37.000,27.000,81.000,45.000,17.000,51.000,58.000,62.000,65.000}
-62.470 LMS_LASER_2D_RIGHT LMS2 ID=3962,time=1225719874.107425,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=51,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.412,18.763,15.586,12.801,10.924,9.847,8.911,8.155,7.462,6.851,6.305,5.903,5.510,5.201,4.872,4.605,4.321,4.100,3.937,3.730,3.560,3.390,3.164,3.053,2.944,2.838,2.726,2.633,2.542,2.452,2.389,2.312,2.238,2.156,2.095,2.019,1.970,1.937,1.901,1.856,1.824,1.756,1.696,1.661,1.638,1.605,1.572,1.536,1.510,1.492,1.456,1.423,1.402,1.377,1.366,1.338,1.315,1.306,1.285,1.266,1.253,1.246,1.235,1.256,1.262,1.273,1.286,1.283,1.264,1.250,1.224,1.215,1.204,1.195,1.178,1.146,1.134,1.124,1.122,1.122,1.080,1.072,1.091,1.090,1.067,1.065,1.057,1.052,1.040,1.029,1.027,1.015,0.979},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,9.000,123.000,111.000,84.000,63.000,58.000,57.000,54.000,61.000,66.000,66.000,67.000,68.000,70.000,72.000,71.000,73.000,77.000,76.000,77.000,77.000,78.000,80.000,78.000,80.000,81.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,78.000,78.000,79.000,80.000,81.000,79.000,79.000,79.000,79.000,78.000,77.000,68.000,70.000,78.000,78.000,77.000,77.000,75.000,75.000,76.000,77.000,72.000,63.000,53.000,50.000,44.000,47.000,51.000,52.000,60.000,56.000,63.000,58.000,55.000,39.000,43.000,46.000,37.000,42.000,28.000,29.000,41.000,42.000,41.000,42.000,38.000,39.000,34.000,32.000,37.000,33.000,28.000}
-62.482 LMS_LASER_2D_LEFT LMS1 ID=4091,time=1225719874.128586,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=88,Range=[181]{1.067,1.073,1.072,1.090,1.094,1.101,1.112,1.124,1.136,1.149,1.162,1.169,1.191,1.190,1.214,1.221,1.224,1.213,1.238,1.269,1.277,1.306,1.314,1.328,1.358,1.371,1.391,1.400,1.434,1.440,1.456,1.471,1.504,1.537,1.564,1.591,1.609,1.635,1.654,1.689,1.724,1.759,1.805,1.840,1.883,1.929,1.955,1.987,2.041,2.082,2.142,2.187,2.230,2.292,2.351,2.408,2.477,2.539,2.599,2.667,2.757,2.830,2.851,2.843,2.857,3.013,3.109,3.167,3.240,3.389,3.483,3.646,3.916,4.052,4.150,4.168,4.179,4.174,4.207,4.238,4.254,4.246,4.249,4.261,4.266,4.254,4.283,4.325,4.352,4.349,4.375,4.380,4.380,4.376,4.376,4.385,4.385,4.385,4.393,4.394,4.400,4.400,4.401,4.411,4.420,4.419,4.428,4.438,4.437,4.454,4.468,4.479,4.478,4.490,4.499,4.500,4.520,4.530,4.537,4.548,4.564,4.573,4.585,4.594,2.601,2.670,2.729,3.554,3.069,3.246,3.286,3.153,2.970,2.927,2.947,3.261,3.999,4.301,2.923,2.841,2.854,2.864,2.886,2.808,3.106,3.609,3.162,2.915,2.759,2.806,2.975,3.004,2.955,3.173,3.291,5.273,5.301,5.330,5.368,5.400,5.440,5.472,2.518,5.542,5.568,2.422,5.638,5.617,5.610,5.819,6.624,6.677,6.719,6.775,5.432,5.432,2.279,2.161,2.129,2.157,2.180},Reflectance=[181]{43.000,45.000,46.000,45.000,44.000,48.000,44.000,42.000,44.000,46.000,49.000,48.000,42.000,50.000,46.000,44.000,53.000,56.000,52.000,42.000,45.000,48.000,47.000,50.000,51.000,52.000,53.000,53.000,54.000,52.000,55.000,55.000,54.000,53.000,53.000,54.000,55.000,58.000,55.000,54.000,54.000,54.000,54.000,54.000,49.000,51.000,54.000,57.000,55.000,54.000,54.000,55.000,54.000,50.000,46.000,47.000,45.000,46.000,49.000,46.000,43.000,52.000,54.000,54.000,56.000,46.000,54.000,56.000,53.000,45.000,55.000,55.000,59.000,49.000,46.000,67.000,73.000,71.000,71.000,72.000,74.000,75.000,75.000,74.000,73.000,72.000,70.000,72.000,74.000,73.000,76.000,77.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,41.000,100.000,125.000,95.000,90.000,105.000,101.000,89.000,84.000,76.000,79.000,94.000,96.000,95.000,117.000,80.000,94.000,95.000,100.000,74.000,91.000,90.000,101.000,103.000,73.000,61.000,46.000,55.000,40.000,21.000,32.000,76.000,76.000,75.000,75.000,74.000,72.000,71.000,20.000,63.000,64.000,35.000,63.000,68.000,60.000,59.000,49.000,53.000,43.000,46.000,80.000,83.000,30.000,70.000,60.000,65.000,68.000}
-62.499 DESIRED_THRUST iJoystick 84.5393230995
-62.499 DESIRED_RUDDER iJoystick 4.12305063021
-62.482 LMS_LASER_2D_RIGHT LMS2 ID=3963,time=1225719874.120771,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=52,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.476,20.996,16.129,13.097,11.291,10.004,9.077,8.341,7.568,6.958,6.417,5.980,5.586,5.255,4.935,4.663,4.375,4.117,3.961,3.778,3.593,3.440,3.243,3.100,2.979,2.852,2.743,2.652,2.560,2.470,2.398,2.322,2.256,2.166,2.103,2.053,1.985,1.946,1.910,1.856,1.824,1.767,1.697,1.670,1.636,1.605,1.576,1.543,1.516,1.494,1.467,1.437,1.387,1.370,1.364,1.347,1.317,1.305,1.285,1.266,1.262,1.252,1.243,1.253,1.264,1.273,1.283,1.282,1.265,1.250,1.231,1.213,1.197,1.194,1.187,1.160,1.124,1.133,1.129,1.113,1.116,1.062,1.095,1.088,1.073,1.068,1.057,1.059,1.044,1.048,1.030,1.029,1.018},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,20.000,112.000,119.000,84.000,67.000,59.000,56.000,53.000,60.000,64.000,65.000,67.000,68.000,70.000,71.000,72.000,73.000,75.000,75.000,76.000,77.000,78.000,78.000,79.000,79.000,81.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,81.000,80.000,78.000,78.000,79.000,79.000,78.000,73.000,74.000,78.000,78.000,77.000,76.000,75.000,75.000,77.000,76.000,71.000,61.000,54.000,50.000,47.000,43.000,54.000,60.000,59.000,64.000,66.000,62.000,55.000,43.000,41.000,46.000,45.000,56.000,38.000,27.000,40.000,45.000,46.000,43.000,38.000,41.000,37.000,41.000,45.000,45.000,37.000}
-62.494 LMS_LASER_2D_LEFT LMS1 ID=4092,time=1225719874.141922,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=89,Range=[181]{1.056,1.072,1.077,1.081,1.093,1.105,1.116,1.119,1.128,1.146,1.157,1.171,1.185,1.187,1.212,1.209,1.214,1.213,1.232,1.260,1.282,1.296,1.308,1.331,1.349,1.370,1.382,1.400,1.420,1.442,1.456,1.477,1.510,1.521,1.555,1.574,1.607,1.622,1.657,1.680,1.727,1.766,1.787,1.832,1.867,1.919,1.952,1.978,2.024,2.077,2.099,2.169,2.212,2.267,2.330,2.395,2.463,2.520,2.581,2.652,2.733,2.815,2.850,2.843,2.849,2.952,3.091,3.165,3.227,3.389,3.458,3.585,3.853,4.011,4.117,4.166,4.174,4.168,4.187,4.226,4.246,4.245,4.248,4.245,4.259,4.246,4.267,4.312,4.344,4.343,4.357,4.375,4.369,4.373,4.376,4.376,4.376,4.385,4.385,4.394,4.391,4.391,4.401,4.403,4.410,4.410,4.421,4.421,4.430,4.438,4.448,4.454,4.464,4.480,4.489,4.501,4.510,4.521,4.530,4.540,4.548,4.564,4.583,4.586,2.589,2.676,2.583,2.684,2.820,2.771,3.087,3.084,2.938,2.930,3.013,3.833,2.963,2.912,2.921,2.836,2.892,2.868,2.892,2.936,3.058,3.401,3.179,3.159,2.806,2.923,2.959,2.924,2.933,2.957,5.236,5.261,5.290,5.324,5.350,5.384,5.424,5.457,2.525,5.516,5.559,2.388,5.621,5.624,5.604,5.688,6.037,6.672,6.759,6.788,5.457,5.425,2.293,2.250,2.202,2.216,2.223},Reflectance=[181]{45.000,41.000,39.000,45.000,43.000,41.000,41.000,48.000,44.000,44.000,46.000,44.000,43.000,44.000,44.000,51.000,53.000,56.000,53.000,47.000,49.000,47.000,52.000,47.000,47.000,52.000,49.000,50.000,51.000,53.000,56.000,53.000,53.000,54.000,53.000,54.000,54.000,56.000,56.000,54.000,51.000,53.000,54.000,51.000,54.000,46.000,53.000,57.000,55.000,52.000,54.000,55.000,54.000,54.000,48.000,41.000,43.000,41.000,49.000,48.000,40.000,49.000,50.000,50.000,57.000,54.000,46.000,51.000,51.000,45.000,51.000,55.000,57.000,51.000,47.000,65.000,71.000,72.000,70.000,71.000,72.000,74.000,75.000,74.000,73.000,72.000,70.000,70.000,75.000,74.000,76.000,78.000,76.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,23.000,105.000,75.000,85.000,83.000,82.000,75.000,86.000,77.000,77.000,88.000,72.000,106.000,92.000,89.000,81.000,98.000,99.000,97.000,105.000,89.000,77.000,93.000,97.000,62.000,52.000,39.000,56.000,53.000,19.000,76.000,75.000,76.000,75.000,75.000,75.000,73.000,72.000,14.000,65.000,62.000,29.000,62.000,67.000,63.000,53.000,54.000,38.000,31.000,33.000,75.000,78.000,42.000,72.000,72.000,73.000,59.000}
-62.494 LMS_LASER_2D_RIGHT LMS2 ID=3964,time=1225719874.134116,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=53,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.722,13.459,11.723,10.286,9.345,8.554,7.727,7.084,6.580,6.061,5.664,5.318,5.016,4.723,4.430,4.185,4.003,3.815,3.642,3.480,3.295,3.136,2.975,2.887,2.767,2.687,2.595,2.497,2.407,2.357,2.275,2.201,2.121,2.051,2.002,1.954,1.918,1.873,1.832,1.783,1.710,1.677,1.653,1.610,1.581,1.552,1.526,1.500,1.475,1.447,1.416,1.374,1.361,1.346,1.324,1.303,1.282,1.270,1.257,1.256,1.244,1.249,1.263,1.279,1.282,1.278,1.274,1.249,1.235,1.213,1.198,1.203,1.187,1.163,1.129,1.129,1.134,1.125,1.113,1.075,1.096,1.088,1.073,1.075,1.059,1.058,1.053,1.049,1.027,1.017,1.020},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,94.000,127.000,90.000,72.000,58.000,56.000,57.000,59.000,63.000,66.000,67.000,68.000,69.000,71.000,73.000,72.000,75.000,76.000,75.000,78.000,77.000,78.000,80.000,77.000,79.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,80.000,78.000,77.000,78.000,79.000,80.000,79.000,78.000,79.000,79.000,79.000,78.000,77.000,75.000,77.000,78.000,77.000,76.000,74.000,76.000,78.000,77.000,73.000,66.000,58.000,49.000,47.000,45.000,47.000,60.000,61.000,65.000,68.000,62.000,55.000,40.000,40.000,44.000,41.000,50.000,48.000,28.000,40.000,49.000,49.000,43.000,39.000,43.000,40.000,43.000,51.000,54.000,52.000}
-62.503 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.7410,19.0418,-0.8188},Vel=[3x1]{-0.8339,-0.7800,11.2821},Raw=[2x1]{20.7169,-0.8188},time=1225719874.15038657188416,Speed=1.14190590228089,Pitch=0.00897341493535,Roll=0.04486707467677,PitchDot=0.02243353733839,RollDot=-0.00136844577764
-62.503 ODOMETRY_POSE iPlatform Pose=[3x1]{4.7410,19.0418,-0.8181},Vel=[3x1]{-0.8339,-0.7800,-1.2844},Raw=[2x1]{20.7169,-0.8188},time=1225719874.1504,Speed=1.1419,Pitch=-0.0266,Roll=0.0372,PitchDot=0.0077,RollDot=0.0211
-62.506 LMS_LASER_2D_LEFT LMS1 ID=4093,time=1225719874.155257,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=90,Range=[181]{1.060,1.066,1.077,1.077,1.094,1.099,1.113,1.119,1.135,1.141,1.153,1.166,1.175,1.182,1.183,1.205,1.220,1.230,1.237,1.262,1.275,1.294,1.310,1.326,1.342,1.360,1.374,1.389,1.413,1.434,1.452,1.468,1.488,1.514,1.547,1.573,1.597,1.614,1.644,1.671,1.721,1.741,1.784,1.823,1.860,1.888,1.928,1.967,2.006,2.056,2.105,2.162,2.187,2.251,2.307,2.377,2.446,2.496,2.562,2.621,2.693,2.797,2.834,2.833,2.827,2.898,3.055,3.143,3.216,3.354,3.434,3.511,3.785,3.983,4.091,4.163,4.163,4.158,4.166,4.201,4.229,4.234,4.236,4.238,4.250,4.247,4.246,4.292,4.333,4.338,4.347,4.364,4.363,4.371,4.370,4.374,4.374,4.374,4.375,4.375,4.384,4.383,4.391,4.392,4.401,4.403,4.411,4.410,4.420,4.434,4.439,4.446,4.457,4.462,4.482,4.487,4.498,4.509,4.518,4.530,4.547,4.553,4.565,4.575,4.594,2.721,2.654,2.603,2.729,2.723,2.820,3.070,2.949,2.933,3.053,3.838,2.822,2.727,2.737,2.751,2.763,2.731,2.755,2.930,2.978,3.275,3.249,3.242,5.052,3.072,2.992,2.934,2.937,2.970,5.216,5.243,5.279,5.299,5.330,5.365,5.401,5.436,5.472,5.507,5.547,2.383,5.569,5.620,5.605,5.628,5.868,6.676,5.427,5.406,5.467,5.392,2.296,2.247,2.254,2.246,5.459},Reflectance=[181]{39.000,42.000,39.000,44.000,39.000,38.000,35.000,39.000,48.000,41.000,44.000,46.000,47.000,50.000,47.000,49.000,48.000,49.000,48.000,43.000,49.000,46.000,50.000,49.000,48.000,51.000,54.000,52.000,52.000,54.000,54.000,53.000,55.000,55.000,54.000,54.000,56.000,57.000,54.000,54.000,52.000,54.000,53.000,51.000,54.000,55.000,54.000,56.000,54.000,54.000,49.000,55.000,55.000,55.000,49.000,40.000,40.000,43.000,44.000,50.000,42.000,46.000,54.000,50.000,55.000,56.000,46.000,46.000,54.000,46.000,49.000,55.000,45.000,45.000,43.000,60.000,70.000,71.000,69.000,69.000,72.000,73.000,74.000,75.000,76.000,72.000,67.000,70.000,76.000,75.000,73.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,76.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,127.000,93.000,75.000,87.000,78.000,83.000,76.000,78.000,78.000,94.000,71.000,97.000,74.000,74.000,76.000,76.000,75.000,74.000,93.000,80.000,65.000,69.000,102.000,75.000,49.000,56.000,61.000,58.000,13.000,75.000,75.000,75.000,73.000,69.000,65.000,65.000,66.000,62.000,63.000,60.000,20.000,67.000,69.000,67.000,60.000,49.000,34.000,24.000,35.000,67.000,43.000,44.000,67.000,74.000,64.000,36.000}
-62.506 LMS_LASER_2D_RIGHT LMS2 ID=3965,time=1225719874.147460,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=54,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.897,17.567,14.566,12.224,10.577,9.569,8.743,7.925,7.244,6.696,6.180,5.767,5.407,5.111,4.782,4.509,4.239,4.049,3.853,3.687,3.523,3.352,3.164,3.054,2.923,2.790,2.705,2.625,2.525,2.442,2.372,2.310,2.218,2.139,2.070,2.019,1.969,1.928,1.884,1.842,1.812,1.737,1.695,1.658,1.616,1.589,1.562,1.525,1.509,1.472,1.455,1.427,1.382,1.357,1.334,1.316,1.297,1.279,1.271,1.268,1.257,1.251,1.249,1.257,1.271,1.283,1.288,1.276,1.269,1.233,1.206,1.192,1.196,1.192,1.166,1.137,1.127,1.128,1.132,1.115,1.108,1.095,1.087,1.079,1.073,1.065,1.060,1.058,1.044,1.034,1.017,1.014},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,67.000,118.000,96.000,78.000,60.000,57.000,57.000,56.000,63.000,65.000,66.000,68.000,68.000,70.000,72.000,72.000,75.000,77.000,75.000,78.000,78.000,78.000,80.000,77.000,78.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,77.000,76.000,77.000,77.000,76.000,76.000,77.000,78.000,78.000,71.000,66.000,59.000,49.000,47.000,42.000,39.000,48.000,60.000,67.000,71.000,66.000,53.000,40.000,37.000,44.000,42.000,40.000,53.000,41.000,39.000,48.000,48.000,42.000,41.000,44.000,43.000,40.000,51.000,54.000,53.000}
-62.518 LMS_LASER_2D_LEFT LMS1 ID=4094,time=1225719874.168592,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=91,Range=[181]{1.057,1.060,1.071,1.075,1.091,1.090,1.111,1.112,1.125,1.136,1.142,1.157,1.169,1.177,1.193,1.207,1.221,1.232,1.242,1.251,1.271,1.283,1.294,1.315,1.331,1.346,1.371,1.383,1.409,1.424,1.442,1.468,1.495,1.520,1.530,1.556,1.596,1.613,1.642,1.671,1.712,1.733,1.759,1.810,1.845,1.877,1.921,1.956,1.989,2.040,2.095,2.143,2.177,2.236,2.290,2.355,2.430,2.486,2.545,2.613,2.673,2.754,2.820,2.833,2.826,2.875,3.023,3.102,3.187,3.274,3.324,3.515,3.707,3.904,4.046,4.141,4.152,4.153,4.158,4.195,4.229,4.232,4.237,4.237,4.242,4.246,4.233,4.269,4.315,4.339,4.324,4.353,4.364,4.360,4.368,4.368,4.372,4.374,4.376,4.366,4.375,4.385,4.384,4.391,4.394,4.394,4.403,4.412,4.420,4.427,4.430,4.438,4.447,4.456,4.473,4.479,4.491,4.500,4.509,4.519,4.535,4.546,4.553,4.567,4.582,2.770,2.625,2.716,2.708,2.787,2.739,3.069,2.956,2.935,3.040,3.946,2.941,2.802,2.731,2.736,2.744,2.724,2.716,2.755,2.933,3.318,3.201,3.207,3.426,3.052,3.110,2.965,2.932,2.915,5.199,5.227,5.262,5.287,5.320,5.347,5.373,5.419,5.462,5.506,5.533,5.568,5.547,5.612,5.610,5.597,5.739,6.666,5.444,5.447,5.467,5.408,5.364,2.362,2.330,2.345,5.454},Reflectance=[181]{38.000,39.000,35.000,43.000,38.000,33.000,44.000,44.000,47.000,44.000,47.000,45.000,48.000,43.000,43.000,41.000,44.000,49.000,46.000,45.000,43.000,49.000,50.000,48.000,51.000,53.000,49.000,54.000,54.000,53.000,53.000,53.000,54.000,53.000,54.000,54.000,52.000,56.000,53.000,54.000,52.000,54.000,54.000,49.000,49.000,54.000,55.000,55.000,54.000,54.000,52.000,55.000,54.000,53.000,49.000,43.000,38.000,45.000,44.000,45.000,49.000,49.000,51.000,50.000,54.000,57.000,51.000,47.000,57.000,56.000,56.000,44.000,43.000,45.000,41.000,54.000,69.000,70.000,69.000,70.000,72.000,73.000,74.000,74.000,76.000,75.000,68.000,69.000,74.000,76.000,74.000,77.000,78.000,76.000,76.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,21.000,39.000,116.000,93.000,92.000,79.000,75.000,77.000,79.000,92.000,94.000,118.000,87.000,75.000,74.000,74.000,76.000,76.000,74.000,87.000,79.000,73.000,94.000,37.000,18.000,108.000,59.000,56.000,33.000,76.000,76.000,76.000,75.000,72.000,64.000,65.000,65.000,61.000,61.000,61.000,61.000,68.000,65.000,68.000,58.000,45.000,29.000,26.000,74.000,70.000,32.000,38.000,54.000,72.000,41.000,65.000}
-62.519 LMS_LASER_2D_RIGHT LMS2 ID=3966,time=1225719874.160802,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=55,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.010,18.465,15.362,12.715,10.895,9.811,8.920,8.096,7.402,6.834,6.289,5.884,5.510,5.191,4.855,4.588,4.301,4.082,3.908,3.730,3.553,3.396,3.200,3.071,2.960,2.812,2.726,2.642,2.542,2.468,2.383,2.320,2.239,2.165,2.093,2.027,1.985,1.944,1.901,1.858,1.813,1.746,1.718,1.664,1.635,1.599,1.572,1.550,1.513,1.482,1.466,1.437,1.388,1.364,1.343,1.315,1.305,1.289,1.272,1.259,1.257,1.244,1.256,1.264,1.275,1.292,1.281,1.279,1.275,1.244,1.208,1.200,1.205,1.204,1.173,1.139,1.135,1.136,1.129,1.122,1.118,1.105,1.083,1.079,1.077,1.063,1.070,1.057,1.052,1.030,1.024,1.019},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,24.000,30.000,119.000,108.000,83.000,64.000,58.000,57.000,54.000,61.000,66.000,65.000,67.000,68.000,70.000,72.000,72.000,74.000,76.000,76.000,78.000,78.000,78.000,80.000,78.000,77.000,78.000,80.000,80.000,80.000,81.000,81.000,81.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,77.000,77.000,79.000,79.000,79.000,78.000,77.000,78.000,79.000,78.000,76.000,75.000,77.000,77.000,76.000,77.000,77.000,78.000,78.000,74.000,63.000,58.000,51.000,43.000,40.000,40.000,43.000,57.000,70.000,72.000,65.000,51.000,40.000,37.000,44.000,44.000,33.000,49.000,43.000,42.000,50.000,48.000,44.000,40.000,44.000,43.000,42.000,49.000,53.000,51.000}
-62.523 DESIRED_THRUST iJoystick 84.5393230995
-62.523 DESIRED_RUDDER iJoystick 4.12305063021
-62.519 LMS_LASER_2D_RIGHT LMS2 ID=3967,time=1225719874.174131,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=56,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.158,-1.000,16.014,13.063,11.277,10.037,9.202,8.342,7.588,6.965,6.442,5.998,5.604,5.273,4.936,4.655,4.367,4.134,3.975,3.770,3.599,3.444,3.263,3.111,2.979,2.831,2.746,2.660,2.570,2.483,2.414,2.337,2.266,2.193,2.113,2.044,1.993,1.954,1.918,1.866,1.824,1.767,1.725,1.678,1.635,1.607,1.584,1.562,1.518,1.494,1.470,1.435,1.396,1.381,1.362,1.324,1.303,1.289,1.271,1.262,1.263,1.253,1.257,1.265,1.268,1.285,1.286,1.287,1.265,1.249,1.232,1.223,1.213,1.207,1.182,1.147,1.143,1.133,1.123,1.083,1.083,1.103,1.082,1.084,1.085,1.076,1.066,1.052,1.044,1.029,1.026,1.012},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,27.000,0.000,114.000,122.000,82.000,67.000,57.000,56.000,54.000,60.000,65.000,66.000,67.000,69.000,70.000,72.000,72.000,73.000,75.000,75.000,75.000,78.000,78.000,79.000,79.000,78.000,79.000,80.000,81.000,79.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,79.000,79.000,80.000,79.000,73.000,74.000,78.000,75.000,76.000,77.000,77.000,76.000,76.000,73.000,77.000,77.000,77.000,73.000,66.000,58.000,52.000,44.000,44.000,45.000,54.000,59.000,60.000,59.000,55.000,45.000,45.000,40.000,43.000,43.000,32.000,27.000,28.000,48.000,57.000,50.000,44.000,41.000,43.000,42.000,37.000,34.000,54.000,56.000}
-62.530 LMS_LASER_2D_LEFT LMS1 ID=4095,time=1225719874.181924,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=92,Range=[181]{1.053,1.058,1.067,1.068,1.084,1.098,1.107,1.114,1.124,1.137,1.138,1.155,1.164,1.175,1.186,1.198,1.224,1.225,1.243,1.256,1.260,1.275,1.303,1.308,1.329,1.351,1.365,1.376,1.400,1.424,1.443,1.460,1.477,1.503,1.529,1.545,1.576,1.596,1.633,1.662,1.703,1.720,1.741,1.793,1.835,1.876,1.912,1.954,1.979,2.032,2.075,2.125,2.167,2.212,2.258,2.325,2.389,2.464,2.521,2.583,2.657,2.730,2.786,2.828,2.820,2.846,2.987,3.082,3.158,3.212,3.306,3.482,3.652,3.827,4.019,4.119,4.141,4.147,4.142,4.172,4.212,4.225,4.228,4.226,4.231,4.241,4.219,4.250,4.299,4.332,4.330,4.339,4.362,4.361,4.361,4.361,4.365,4.358,4.363,4.368,4.366,4.367,4.376,4.375,4.384,4.385,4.394,4.393,4.401,4.411,4.420,4.430,4.437,4.447,4.460,4.473,4.480,4.491,4.500,4.516,4.527,4.535,4.545,4.556,4.574,2.749,2.641,2.563,2.717,2.907,2.799,3.000,2.972,2.930,3.052,4.746,3.814,2.854,2.747,2.755,2.746,2.735,2.732,2.754,3.002,3.334,3.138,3.262,3.503,3.019,3.122,2.977,2.980,2.898,5.183,5.220,5.245,5.270,5.305,5.327,5.367,5.392,5.443,5.486,5.513,5.553,5.542,5.595,5.606,5.595,5.631,5.944,6.676,5.426,5.401,5.460,5.364,2.342,2.334,5.341,5.466},Reflectance=[181]{44.000,43.000,39.000,43.000,43.000,41.000,41.000,41.000,45.000,40.000,46.000,46.000,50.000,50.000,48.000,46.000,45.000,46.000,41.000,49.000,47.000,46.000,45.000,49.000,46.000,43.000,46.000,51.000,53.000,50.000,54.000,54.000,53.000,53.000,53.000,57.000,55.000,56.000,53.000,54.000,52.000,56.000,58.000,49.000,52.000,54.000,54.000,54.000,54.000,55.000,51.000,54.000,54.000,54.000,54.000,53.000,45.000,44.000,46.000,50.000,45.000,47.000,55.000,51.000,51.000,56.000,54.000,46.000,56.000,60.000,56.000,45.000,45.000,43.000,45.000,55.000,65.000,70.000,69.000,70.000,72.000,73.000,74.000,74.000,75.000,75.000,69.000,68.000,72.000,76.000,75.000,76.000,77.000,77.000,77.000,77.000,78.000,79.000,77.000,79.000,78.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,29.000,51.000,71.000,109.000,96.000,82.000,78.000,79.000,77.000,101.000,77.000,100.000,110.000,77.000,76.000,77.000,76.000,75.000,74.000,119.000,104.000,75.000,95.000,32.000,37.000,96.000,61.000,51.000,33.000,76.000,76.000,76.000,75.000,75.000,69.000,70.000,66.000,60.000,59.000,60.000,58.000,69.000,62.000,67.000,63.000,54.000,48.000,37.000,71.000,66.000,75.000,36.000,65.000,71.000,40.000,67.000}
-62.539 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.7745,19.0729,-0.8259},Vel=[3x1]{-0.8534,-0.7870,13.2051},Raw=[2x1]{20.7626,-0.8259},time=1225719874.18641853332520,Speed=1.16088899272802,Pitch=0.00897341493535,Roll=0.04038036720910,PitchDot=0.04486707467677,RollDot=-0.00154791407635
-62.539 ODOMETRY_POSE iPlatform Pose=[3x1]{4.7745,19.0729,-0.8253},Vel=[3x1]{-0.8534,-0.7870,0.6392},Raw=[2x1]{20.7626,-0.8259},time=1225719874.1864,Speed=1.1609,Pitch=-0.0236,Roll=0.0340,PitchDot=0.0351,RollDot=-0.0280
-62.542 LMS_LASER_2D_RIGHT LMS2 ID=3968,time=1225719874.187470,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=57,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.427,-1.000,16.818,13.911,11.814,10.374,9.410,8.579,7.726,7.084,6.606,6.089,5.689,5.336,5.024,4.732,4.447,4.194,4.019,3.813,3.634,3.470,3.323,3.146,3.018,2.887,2.775,2.687,2.606,2.495,2.430,2.362,2.292,2.209,2.139,2.068,2.010,1.961,1.927,1.884,1.838,1.767,1.732,1.690,1.643,1.607,1.590,1.563,1.532,1.501,1.475,1.447,1.414,1.382,1.364,1.342,1.308,1.288,1.280,1.266,1.263,1.257,1.250,1.274,1.276,1.291,1.292,1.270,1.256,1.247,1.230,1.230,1.227,1.210,1.190,1.163,1.139,1.135,1.125,1.122,1.121,1.098,1.086,1.086,1.080,1.076,1.073,1.057,1.052,1.045,1.029,1.018},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,0.000,89.000,116.000,90.000,72.000,59.000,55.000,56.000,59.000,63.000,66.000,67.000,69.000,69.000,70.000,72.000,73.000,74.000,75.000,76.000,78.000,78.000,78.000,80.000,77.000,79.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,74.000,74.000,70.000,73.000,77.000,78.000,77.000,74.000,72.000,76.000,78.000,77.000,75.000,68.000,58.000,52.000,51.000,47.000,57.000,63.000,63.000,63.000,59.000,49.000,46.000,49.000,45.000,40.000,44.000,33.000,32.000,44.000,57.000,59.000,51.000,40.000,39.000,46.000,41.000,37.000,37.000,48.000,55.000}
-62.547 DESIRED_THRUST iJoystick 84.5393230995
-62.547 DESIRED_RUDDER iJoystick 4.12305063021
-62.542 LMS_LASER_2D_LEFT LMS1 ID=4096,time=1225719874.195255,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=93,Range=[181]{1.050,1.055,1.061,1.067,1.069,1.094,1.096,1.109,1.122,1.128,1.139,1.147,1.166,1.166,1.186,1.199,1.199,1.214,1.227,1.245,1.262,1.271,1.280,1.302,1.315,1.335,1.352,1.368,1.390,1.408,1.425,1.443,1.468,1.495,1.511,1.539,1.566,1.595,1.615,1.643,1.694,1.715,1.723,1.769,1.823,1.865,1.894,1.943,1.978,2.017,2.063,2.107,2.150,2.189,2.241,2.311,2.370,2.443,2.502,2.552,2.630,2.711,2.762,2.812,2.819,2.833,2.954,3.062,3.149,3.232,3.340,3.446,3.584,3.759,3.928,4.092,4.149,4.140,4.137,4.154,4.199,4.211,4.219,4.219,4.222,4.240,4.217,4.225,4.278,4.321,4.323,4.324,4.353,4.361,4.361,4.353,4.354,4.358,4.361,4.355,4.358,4.366,4.367,4.376,4.376,4.385,4.385,4.394,4.394,4.403,4.410,4.421,4.430,4.439,4.445,4.457,4.474,4.475,4.491,4.501,4.518,4.527,4.537,4.546,4.567,4.574,2.591,2.658,2.578,2.765,2.821,3.212,3.059,2.936,3.063,4.019,3.994,4.766,2.862,2.768,2.764,2.830,2.729,2.841,2.851,3.137,3.144,3.176,3.046,2.936,2.977,3.116,2.999,2.950,5.167,5.192,5.229,5.253,5.288,5.325,5.347,5.377,5.428,5.463,5.489,5.517,5.540,5.551,5.612,5.604,5.596,5.818,6.648,5.383,5.387,5.437,2.399,2.333,2.346,5.347,5.410},Reflectance=[181]{43.000,38.000,40.000,43.000,49.000,39.000,46.000,43.000,41.000,40.000,45.000,46.000,45.000,42.000,43.000,45.000,50.000,49.000,47.000,43.000,48.000,48.000,48.000,49.000,48.000,49.000,52.000,51.000,53.000,53.000,54.000,54.000,53.000,54.000,53.000,54.000,54.000,56.000,53.000,54.000,48.000,53.000,65.000,54.000,47.000,53.000,54.000,53.000,53.000,55.000,53.000,54.000,54.000,56.000,55.000,47.000,50.000,43.000,45.000,52.000,45.000,45.000,57.000,55.000,51.000,57.000,51.000,49.000,52.000,50.000,48.000,46.000,47.000,45.000,43.000,51.000,61.000,68.000,67.000,68.000,73.000,72.000,74.000,74.000,72.000,75.000,69.000,66.000,71.000,75.000,76.000,76.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,53.000,98.000,70.000,122.000,124.000,114.000,107.000,76.000,110.000,99.000,100.000,78.000,118.000,78.000,77.000,98.000,75.000,99.000,58.000,87.000,107.000,97.000,50.000,35.000,58.000,105.000,49.000,20.000,76.000,76.000,76.000,76.000,75.000,70.000,72.000,70.000,63.000,62.000,64.000,67.000,68.000,67.000,63.000,63.000,58.000,47.000,35.000,65.000,67.000,76.000,11.000,66.000,55.000,58.000,65.000}
-62.554 LMS_LASER_2D_RIGHT LMS2 ID=3969,time=1225719874.200808,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=58,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.548,17.961,14.710,12.444,10.694,9.647,8.779,7.947,7.271,6.741,6.190,5.803,5.433,5.119,4.808,4.526,4.265,4.064,3.857,3.690,3.511,3.362,3.176,3.060,2.928,2.801,2.722,2.626,2.525,2.441,2.385,2.309,2.237,2.156,2.093,2.025,1.977,1.925,1.884,1.841,1.794,1.750,1.708,1.662,1.624,1.597,1.579,1.532,1.513,1.493,1.464,1.438,1.401,1.377,1.347,1.319,1.290,1.281,1.276,1.257,1.249,1.251,1.269,1.275,1.280,1.276,1.258,1.249,1.247,1.232,1.237,1.221,1.222,1.200,1.176,1.141,1.142,1.137,1.133,1.111,1.100,1.090,1.097,1.077,1.069,1.071,1.066,1.055,1.036,1.025,1.032},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,26.000,53.000,116.000,97.000,81.000,63.000,56.000,58.000,57.000,63.000,67.000,66.000,68.000,68.000,70.000,72.000,73.000,73.000,75.000,76.000,77.000,78.000,78.000,79.000,79.000,79.000,80.000,80.000,81.000,77.000,79.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,70.000,70.000,75.000,76.000,75.000,75.000,74.000,77.000,78.000,78.000,75.000,70.000,60.000,51.000,50.000,56.000,66.000,66.000,63.000,66.000,62.000,55.000,44.000,46.000,41.000,38.000,47.000,42.000,43.000,55.000,58.000,57.000,49.000,35.000,39.000,45.000,43.000,38.000,32.000,33.000,36.000}
-62.554 LMS_LASER_2D_LEFT LMS1 ID=4097,time=1225719874.208585,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=94,Range=[181]{1.037,1.052,1.058,1.067,1.083,1.077,1.092,1.107,1.111,1.124,1.136,1.144,1.160,1.169,1.182,1.194,1.204,1.212,1.224,1.236,1.252,1.267,1.282,1.303,1.316,1.335,1.341,1.364,1.390,1.409,1.423,1.442,1.462,1.478,1.506,1.531,1.566,1.591,1.611,1.643,1.671,1.707,1.741,1.745,1.803,1.855,1.891,1.921,1.968,2.007,2.048,2.085,2.126,2.169,2.213,2.294,2.353,2.416,2.481,2.537,2.560,2.675,2.749,2.765,2.810,2.809,2.873,3.043,3.105,3.213,3.281,3.418,3.522,3.715,3.853,4.025,4.143,4.138,4.130,4.145,4.186,4.206,4.211,4.211,4.215,4.232,4.223,4.209,4.250,4.298,4.315,4.313,4.337,4.344,4.349,4.350,4.354,4.353,4.357,4.347,4.352,4.357,4.358,4.367,4.367,4.376,4.376,4.386,4.385,4.402,4.406,4.412,4.420,4.430,4.439,4.448,4.465,4.475,4.482,4.490,4.501,4.521,4.530,4.537,2.591,2.636,2.649,2.666,2.577,2.682,2.778,3.204,2.991,2.939,3.037,3.512,3.003,3.129,3.051,2.927,2.891,2.831,2.700,2.736,2.827,3.112,3.029,2.867,2.912,2.927,2.983,3.084,2.972,3.026,5.153,5.178,5.213,5.238,5.274,5.301,5.340,5.369,5.407,5.443,5.476,5.512,5.539,5.540,5.610,5.604,5.577,5.705,6.623,5.421,5.390,5.392,5.383,2.356,5.402,5.341,5.391},Reflectance=[181]{41.000,36.000,43.000,43.000,42.000,44.000,43.000,42.000,44.000,46.000,44.000,43.000,43.000,39.000,45.000,43.000,44.000,48.000,50.000,43.000,47.000,53.000,44.000,45.000,48.000,52.000,51.000,53.000,53.000,54.000,53.000,53.000,55.000,54.000,55.000,54.000,54.000,54.000,56.000,54.000,54.000,54.000,54.000,56.000,49.000,52.000,53.000,51.000,52.000,55.000,54.000,55.000,54.000,55.000,55.000,51.000,42.000,42.000,43.000,53.000,59.000,45.000,55.000,58.000,51.000,58.000,60.000,52.000,49.000,50.000,48.000,46.000,44.000,43.000,49.000,53.000,58.000,70.000,68.000,70.000,72.000,73.000,74.000,74.000,73.000,75.000,73.000,65.000,68.000,75.000,76.000,76.000,77.000,77.000,76.000,76.000,77.000,77.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,34.000,94.000,98.000,105.000,75.000,94.000,115.000,107.000,78.000,77.000,94.000,99.000,27.000,117.000,84.000,79.000,96.000,113.000,69.000,69.000,77.000,103.000,46.000,65.000,55.000,67.000,75.000,83.000,67.000,48.000,77.000,77.000,77.000,76.000,76.000,71.000,72.000,72.000,70.000,70.000,70.000,75.000,70.000,71.000,60.000,64.000,58.000,50.000,36.000,69.000,68.000,66.000,61.000,23.000,72.000,55.000,56.000}
-62.571 DESIRED_THRUST iJoystick 84.5393230995
-62.571 DESIRED_RUDDER iJoystick 4.12305063021
-62.575 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.8080,19.1036,-0.8331},Vel=[3x1]{-0.8537,-0.7759,9.2308},Raw=[2x1]{20.8080,-0.8331},time=1225719874.22244763374329,Speed=1.15358780409451,Pitch=0.01346012240303,Roll=0.03365030600758,PitchDot=0.07627402695051,RollDot=-0.00163764822570
-62.575 ODOMETRY_POSE iPlatform Pose=[3x1]{4.8080,19.1036,-0.8326},Vel=[3x1]{-0.8537,-0.7759,2.9471},Raw=[2x1]{20.8080,-0.8331},time=1225719874.2224,Speed=1.1536,Pitch=-0.0158,Roll=0.0326,PitchDot=-0.0752,RollDot=-0.0131
-62.566 LMS_LASER_2D_LEFT LMS1 ID=4098,time=1225719874.221914,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=95,Range=[181]{1.037,1.052,1.059,1.065,1.071,1.084,1.089,1.105,1.104,1.120,1.125,1.139,1.151,1.168,1.174,1.181,1.195,1.209,1.221,1.236,1.246,1.268,1.277,1.289,1.303,1.330,1.345,1.363,1.374,1.400,1.408,1.444,1.461,1.472,1.491,1.523,1.547,1.584,1.596,1.626,1.666,1.699,1.720,1.770,1.800,1.835,1.870,1.913,1.939,1.998,2.038,2.075,2.107,2.165,2.196,2.275,2.335,2.400,2.447,2.507,2.569,2.605,2.739,2.772,2.804,2.801,2.845,3.027,3.083,3.173,3.276,3.363,3.478,3.650,3.793,3.966,4.126,4.135,4.127,4.131,4.170,4.192,4.209,4.212,4.211,4.220,4.232,4.199,4.237,4.286,4.310,4.297,4.328,4.341,4.347,4.343,4.345,4.347,4.349,4.348,4.355,4.348,4.349,4.359,4.359,4.367,4.367,4.377,4.388,4.388,4.395,4.403,4.412,4.422,4.433,4.439,4.459,4.466,4.474,4.485,4.503,4.512,4.520,2.613,2.696,2.550,2.532,2.625,2.579,2.583,2.764,2.703,3.098,2.942,3.002,3.063,3.175,3.090,3.002,3.027,3.040,2.789,2.699,2.743,2.979,3.047,3.210,2.980,2.890,3.004,3.115,3.141,2.981,3.004,5.134,5.162,5.196,5.231,5.256,5.288,5.330,5.360,5.396,5.427,5.465,5.495,5.526,5.536,5.576,5.612,5.583,5.622,5.917,5.413,5.410,5.419,5.400,5.390,5.400,5.400,5.342},Reflectance=[181]{41.000,36.000,38.000,42.000,46.000,39.000,41.000,40.000,44.000,44.000,47.000,45.000,43.000,43.000,46.000,46.000,48.000,51.000,49.000,48.000,48.000,45.000,46.000,48.000,50.000,50.000,53.000,53.000,54.000,53.000,53.000,54.000,54.000,55.000,56.000,55.000,54.000,55.000,56.000,54.000,52.000,54.000,56.000,55.000,52.000,48.000,55.000,55.000,55.000,54.000,53.000,55.000,54.000,56.000,55.000,45.000,45.000,43.000,49.000,49.000,55.000,51.000,55.000,57.000,52.000,55.000,59.000,49.000,47.000,51.000,45.000,50.000,49.000,44.000,43.000,54.000,58.000,75.000,70.000,71.000,72.000,74.000,74.000,75.000,74.000,75.000,75.000,66.000,67.000,73.000,77.000,76.000,77.000,79.000,78.000,77.000,77.000,78.000,78.000,78.000,80.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,45.000,107.000,75.000,75.000,92.000,79.000,75.000,118.000,47.000,111.000,78.000,85.000,37.000,122.000,104.000,76.000,93.000,89.000,100.000,71.000,73.000,105.000,45.000,125.000,99.000,68.000,79.000,98.000,97.000,59.000,55.000,77.000,77.000,77.000,77.000,76.000,73.000,72.000,73.000,75.000,74.000,74.000,75.000,72.000,70.000,63.000,63.000,60.000,58.000,59.000,30.000,66.000,66.000,61.000,78.000,71.000,76.000,51.000}
-62.567 LMS_LASER_2D_RIGHT LMS2 ID=3970,time=1225719874.214145,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=59,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.853,19.774,15.450,12.791,10.982,9.883,8.998,8.147,7.454,6.869,6.332,5.919,5.528,5.210,4.881,4.622,4.357,4.100,3.913,3.730,3.575,3.409,3.217,3.103,2.972,2.853,2.731,2.643,2.524,2.456,2.418,2.335,2.265,2.168,2.103,2.034,1.993,1.953,1.901,1.858,1.815,1.762,1.710,1.683,1.635,1.616,1.589,1.554,1.516,1.497,1.478,1.444,1.410,1.379,1.360,1.337,1.315,1.298,1.276,1.259,1.258,1.244,1.265,1.276,1.277,1.265,1.253,1.250,1.241,1.239,1.235,1.226,1.217,1.207,1.176,1.145,1.132,1.139,1.135,1.116,1.103,1.091,1.090,1.088,1.079,1.084,1.071,1.057,1.047,1.033,0.996},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,29.000,16.000,122.000,108.000,81.000,65.000,58.000,57.000,54.000,61.000,66.000,65.000,67.000,68.000,71.000,72.000,71.000,74.000,74.000,76.000,77.000,79.000,78.000,79.000,79.000,79.000,80.000,80.000,80.000,77.000,78.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,76.000,71.000,75.000,77.000,75.000,75.000,74.000,74.000,75.000,77.000,77.000,78.000,78.000,78.000,73.000,63.000,52.000,52.000,63.000,74.000,69.000,68.000,65.000,57.000,57.000,49.000,37.000,36.000,37.000,46.000,48.000,51.000,57.000,59.000,58.000,46.000,37.000,37.000,43.000,45.000,38.000,35.000,33.000,28.000}
-62.577 LMS_LASER_2D_RIGHT LMS2 ID=3971,time=1225719874.227480,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=60,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.837,-1.000,16.180,13.157,11.400,10.142,9.245,8.370,7.625,7.003,6.484,6.024,5.629,5.291,4.954,4.680,4.411,4.163,3.967,3.765,3.611,3.452,3.260,3.138,3.018,2.872,2.760,2.669,2.541,2.473,2.423,2.353,2.276,2.169,2.114,2.053,2.002,1.962,1.918,1.866,1.830,1.777,1.719,1.683,1.654,1.636,1.587,1.560,1.535,1.514,1.485,1.441,1.398,1.384,1.364,1.341,1.323,1.307,1.292,1.269,1.262,1.256,1.250,1.274,1.279,1.279,1.273,1.257,1.258,1.260,1.259,1.233,1.232,1.216,1.192,1.159,1.138,1.135,1.124,1.112,1.104,1.101,1.097,1.088,1.052,1.078,1.068,1.058,1.045,1.039,1.036},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,27.000,0.000,109.000,119.000,85.000,71.000,58.000,57.000,55.000,60.000,64.000,65.000,67.000,68.000,70.000,71.000,72.000,75.000,75.000,76.000,77.000,78.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,74.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,80.000,79.000,79.000,78.000,76.000,71.000,67.000,74.000,74.000,74.000,75.000,75.000,76.000,76.000,77.000,77.000,78.000,79.000,77.000,69.000,58.000,53.000,53.000,62.000,66.000,66.000,56.000,48.000,56.000,44.000,37.000,38.000,36.000,45.000,51.000,57.000,59.000,60.000,58.000,45.000,37.000,28.000,39.000,43.000,41.000,35.000,35.000,35.000}
-62.592 LMS_LASER_2D_LEFT LMS1 ID=4099,time=1225719874.235255,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=96,Range=[181]{1.039,1.047,1.060,1.067,1.073,1.073,1.092,1.090,1.102,1.119,1.124,1.138,1.151,1.163,1.172,1.186,1.194,1.215,1.221,1.236,1.243,1.267,1.268,1.285,1.302,1.315,1.332,1.361,1.366,1.388,1.400,1.425,1.454,1.470,1.495,1.514,1.538,1.574,1.599,1.626,1.663,1.690,1.722,1.759,1.782,1.828,1.867,1.905,1.947,1.987,2.030,2.059,2.100,2.142,2.196,2.254,2.320,2.377,2.438,2.508,2.565,2.607,2.715,2.788,2.805,2.798,2.825,2.984,3.063,3.138,3.234,3.331,3.449,3.597,3.757,3.910,4.084,4.133,4.129,4.123,4.149,4.181,4.202,4.206,4.202,4.211,4.227,4.201,4.217,4.271,4.297,4.301,4.309,4.338,4.344,4.338,4.340,4.346,4.342,4.348,4.343,4.356,4.364,4.358,4.361,4.370,4.368,4.381,4.383,4.383,4.392,4.399,4.403,4.412,4.422,4.442,4.448,4.458,4.464,4.484,4.494,4.517,2.715,2.674,2.632,2.629,2.532,2.611,2.571,2.597,2.715,2.803,3.131,2.952,3.024,4.707,4.724,3.022,3.158,3.201,3.111,2.736,2.796,2.726,2.833,2.959,3.076,2.899,2.985,3.111,3.073,3.029,2.958,2.959,5.130,5.152,5.180,5.216,5.245,5.278,5.317,5.338,5.383,5.417,5.457,5.486,5.516,5.534,5.539,5.604,5.595,5.595,5.822,6.648,5.439,5.437,5.428,5.388,5.442,5.381,5.328},Reflectance=[181]{42.000,45.000,39.000,39.000,42.000,41.000,43.000,41.000,48.000,43.000,46.000,46.000,43.000,44.000,46.000,43.000,48.000,45.000,49.000,48.000,47.000,45.000,46.000,50.000,50.000,48.000,47.000,52.000,54.000,52.000,53.000,54.000,55.000,54.000,54.000,55.000,54.000,54.000,54.000,54.000,55.000,55.000,53.000,50.000,52.000,53.000,54.000,55.000,51.000,53.000,54.000,55.000,51.000,54.000,55.000,49.000,47.000,41.000,44.000,39.000,46.000,52.000,48.000,53.000,52.000,53.000,58.000,57.000,50.000,51.000,51.000,47.000,48.000,44.000,46.000,49.000,51.000,71.000,73.000,69.000,71.000,73.000,74.000,75.000,74.000,74.000,76.000,69.000,66.000,72.000,76.000,78.000,77.000,78.000,77.000,78.000,78.000,79.000,79.000,80.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,80.000,80.000,80.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,79.000,77.000,133.000,119.000,98.000,95.000,75.000,96.000,76.000,78.000,108.000,123.000,118.000,78.000,92.000,76.000,78.000,36.000,121.000,120.000,90.000,53.000,98.000,61.000,50.000,95.000,107.000,44.000,96.000,101.000,35.000,57.000,35.000,29.000,78.000,77.000,78.000,78.000,78.000,75.000,71.000,72.000,74.000,73.000,75.000,75.000,71.000,67.000,68.000,62.000,64.000,61.000,56.000,31.000,67.000,69.000,63.000,73.000,78.000,43.000,41.000}
-62.592 LMS_LASER_2D_RIGHT LMS2 ID=3972,time=1225719874.240815,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=61,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.944,13.967,11.843,10.445,9.466,8.658,7.808,7.169,6.634,6.127,5.741,5.363,5.033,4.765,4.474,4.216,4.011,3.835,3.644,3.489,3.313,3.173,3.050,2.902,2.758,2.670,2.569,2.470,2.411,2.361,2.292,2.188,2.122,2.055,2.019,1.977,1.927,1.884,1.841,1.795,1.732,1.698,1.661,1.633,1.605,1.567,1.542,1.522,1.489,1.457,1.405,1.381,1.378,1.352,1.336,1.317,1.289,1.273,1.261,1.261,1.254,1.260,1.272,1.285,1.295,1.290,1.283,1.277,1.262,1.256,1.243,1.219,1.198,1.173,1.147,1.136,1.128,1.114,1.112,1.116,1.102,1.095,1.087,1.077,1.064,1.061,1.057,1.043,1.033},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,86.000,117.000,91.000,74.000,61.000,55.000,57.000,58.000,63.000,66.000,66.000,68.000,70.000,70.000,72.000,75.000,75.000,74.000,76.000,78.000,77.000,78.000,79.000,79.000,79.000,80.000,80.000,76.000,79.000,80.000,80.000,82.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,75.000,72.000,73.000,74.000,76.000,77.000,77.000,77.000,76.000,77.000,79.000,79.000,77.000,69.000,58.000,48.000,44.000,46.000,47.000,44.000,33.000,43.000,45.000,46.000,48.000,45.000,45.000,51.000,59.000,60.000,55.000,49.000,48.000,42.000,35.000,39.000,35.000,37.000,36.000,35.000,34.000}
-62.595 DESIRED_THRUST iJoystick 84.5393230995
-62.595 DESIRED_RUDDER iJoystick 4.12305063021
-62.606 LMS_LASER_2D_LEFT LMS1 ID=4100,time=1225719874.248597,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=97,Range=[181]{1.033,1.043,1.055,1.067,1.063,1.081,1.084,1.091,1.108,1.114,1.123,1.136,1.156,1.158,1.174,1.174,1.191,1.200,1.212,1.232,1.237,1.263,1.267,1.278,1.294,1.313,1.325,1.353,1.365,1.381,1.406,1.425,1.434,1.460,1.480,1.505,1.531,1.568,1.586,1.611,1.644,1.678,1.712,1.742,1.776,1.808,1.860,1.892,1.933,1.970,2.016,2.055,2.096,2.149,2.186,2.248,2.300,2.358,2.415,2.482,2.552,2.615,2.695,2.776,2.803,2.801,2.824,2.958,3.044,3.091,3.220,3.310,3.423,3.553,3.685,3.846,4.045,4.119,4.134,4.117,4.138,4.182,4.194,4.197,4.196,4.202,4.226,4.202,4.199,4.252,4.284,4.301,4.297,4.331,4.330,4.328,4.332,4.335,4.335,4.332,4.342,4.341,4.348,4.363,4.359,4.354,4.361,4.370,4.377,4.379,4.385,4.401,4.399,4.415,4.422,4.431,4.449,4.448,4.467,4.473,4.488,2.560,2.610,2.526,2.493,2.502,2.492,2.488,2.606,2.668,2.733,2.733,2.797,2.977,3.004,2.971,4.708,4.737,4.745,3.154,3.141,2.729,2.785,2.722,2.878,2.779,3.037,3.158,2.901,2.969,3.015,3.106,3.002,5.087,5.111,5.146,5.172,5.198,5.233,5.268,5.301,5.337,5.369,5.406,5.445,5.471,5.505,5.524,5.530,5.595,5.595,5.568,5.704,6.600,5.499,5.418,5.419,5.411,5.445,5.431,5.389},Reflectance=[181]{39.000,36.000,38.000,38.000,37.000,45.000,43.000,42.000,42.000,45.000,41.000,44.000,37.000,42.000,45.000,46.000,46.000,47.000,48.000,46.000,48.000,43.000,46.000,51.000,50.000,51.000,48.000,52.000,54.000,53.000,49.000,54.000,54.000,54.000,55.000,54.000,54.000,55.000,56.000,55.000,54.000,53.000,52.000,54.000,49.000,56.000,47.000,53.000,52.000,53.000,55.000,53.000,53.000,50.000,50.000,54.000,46.000,49.000,46.000,40.000,43.000,43.000,43.000,48.000,51.000,51.000,58.000,56.000,49.000,46.000,49.000,50.000,49.000,49.000,48.000,50.000,54.000,67.000,74.000,69.000,70.000,74.000,75.000,75.000,75.000,74.000,76.000,72.000,66.000,71.000,75.000,78.000,76.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,79.000,43.000,95.000,76.000,76.000,77.000,76.000,75.000,92.000,98.000,116.000,108.000,115.000,83.000,88.000,24.000,78.000,79.000,79.000,115.000,97.000,45.000,96.000,55.000,116.000,69.000,94.000,119.000,61.000,57.000,16.000,105.000,29.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,74.000,74.000,75.000,76.000,76.000,76.000,73.000,66.000,70.000,63.000,66.000,63.000,53.000,31.000,69.000,69.000,64.000,72.000,76.000,47.000,36.000}
-62.606 LMS_LASER_2D_RIGHT LMS2 ID=3973,time=1225719874.254152,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=62,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.598,17.970,14.549,12.231,10.707,9.665,8.790,7.962,7.287,6.722,6.190,5.811,5.450,5.129,4.817,4.552,4.274,4.057,3.870,3.665,3.534,3.329,3.179,3.076,2.912,2.766,2.688,2.626,2.482,2.402,2.381,2.294,2.213,2.139,2.095,2.028,1.985,1.953,1.892,1.850,1.794,1.740,1.707,1.668,1.639,1.619,1.582,1.541,1.521,1.492,1.466,1.439,1.396,1.385,1.366,1.338,1.327,1.303,1.285,1.271,1.261,1.260,1.255,1.267,1.279,1.293,1.294,1.290,1.275,1.267,1.247,1.231,1.206,1.197,1.182,1.147,1.145,1.138,1.137,1.107,1.080,1.109,1.099,1.094,1.087,1.075,1.061,1.057,1.050,1.047},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,53.000,117.000,98.000,79.000,62.000,57.000,57.000,56.000,62.000,66.000,66.000,68.000,69.000,71.000,72.000,74.000,74.000,74.000,77.000,78.000,77.000,79.000,79.000,79.000,79.000,80.000,80.000,79.000,79.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,78.000,77.000,73.000,74.000,72.000,74.000,76.000,75.000,75.000,77.000,78.000,78.000,79.000,79.000,78.000,74.000,66.000,53.000,43.000,41.000,38.000,34.000,34.000,34.000,39.000,52.000,52.000,40.000,40.000,44.000,37.000,37.000,30.000,28.000,41.000,46.000,41.000,45.000,43.000,42.000,36.000,34.000,38.000}
-62.611 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.8338,19.1269,-0.8376},Vel=[3x1]{-0.8680,-0.7818,6.6667},Raw=[2x1]{20.8428,-0.8376},time=1225719874.25833368301392,Speed=1.16819018136153,Pitch=0.01570347613687,Roll=0.02916359853990,PitchDot=0.06505725828132,RollDot=-0.00170494883772
-62.611 ODOMETRY_POSE iPlatform Pose=[3x1]{4.8338,19.1269,-0.8372},Vel=[3x1]{-0.8680,-0.7818,0.3842},Raw=[2x1]{20.8428,-0.8376},time=1225719874.2583,Speed=1.1682,Pitch=-0.0112,Roll=0.0312,PitchDot=0.0597,RollDot=-0.0260
-62.618 LMS_LASER_2D_LEFT LMS1 ID=4101,time=1225719874.261937,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=98,Range=[181]{1.033,1.038,1.048,1.053,1.069,1.073,1.075,1.089,1.107,1.119,1.126,1.136,1.152,1.153,1.167,1.181,1.184,1.199,1.216,1.227,1.235,1.252,1.259,1.276,1.293,1.314,1.326,1.338,1.364,1.380,1.405,1.417,1.442,1.468,1.487,1.504,1.523,1.557,1.573,1.610,1.633,1.661,1.689,1.733,1.769,1.813,1.843,1.878,1.927,1.970,2.008,2.043,2.090,2.137,2.185,2.239,2.287,2.353,2.413,2.468,2.538,2.609,2.669,2.768,2.797,2.791,2.807,2.902,3.025,3.096,3.181,3.309,3.422,3.536,3.672,3.796,3.992,4.117,4.121,4.118,4.122,4.173,4.188,4.193,4.198,4.194,4.217,4.197,4.190,4.236,4.276,4.292,4.289,4.322,4.318,4.324,4.323,4.338,4.333,4.335,4.337,4.342,4.346,4.352,4.358,4.356,4.358,4.368,4.364,4.376,4.381,4.388,4.399,4.408,4.415,4.424,4.440,4.440,4.451,4.464,4.479,2.676,2.628,2.548,2.464,2.485,2.487,2.482,2.593,2.645,2.584,2.609,2.708,2.746,3.005,2.971,4.711,4.716,2.783,2.830,3.028,2.904,2.823,2.820,2.827,2.769,2.953,3.069,2.892,2.974,2.968,3.094,3.031,5.081,5.103,5.139,5.163,5.193,5.224,5.256,5.293,5.329,5.360,5.392,5.430,5.462,5.498,5.516,5.523,5.585,5.588,5.565,5.628,5.971,5.471,5.437,5.417,5.477,5.460,5.472,5.404},Reflectance=[181]{39.000,41.000,42.000,40.000,44.000,42.000,43.000,41.000,41.000,39.000,43.000,39.000,38.000,44.000,42.000,40.000,47.000,45.000,45.000,43.000,47.000,51.000,50.000,54.000,50.000,51.000,49.000,50.000,49.000,49.000,52.000,54.000,53.000,53.000,54.000,54.000,55.000,54.000,54.000,55.000,58.000,58.000,54.000,54.000,54.000,54.000,55.000,55.000,53.000,50.000,55.000,52.000,47.000,48.000,45.000,50.000,51.000,42.000,37.000,42.000,41.000,44.000,47.000,44.000,53.000,50.000,53.000,50.000,56.000,49.000,46.000,46.000,48.000,50.000,49.000,50.000,46.000,67.000,76.000,70.000,68.000,73.000,75.000,74.000,76.000,75.000,76.000,73.000,66.000,69.000,73.000,78.000,77.000,78.000,77.000,79.000,78.000,80.000,79.000,79.000,79.000,80.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,128.000,111.000,95.000,76.000,77.000,77.000,76.000,96.000,103.000,77.000,77.000,93.000,84.000,89.000,26.000,79.000,78.000,51.000,80.000,117.000,32.000,106.000,95.000,94.000,68.000,74.000,93.000,66.000,56.000,28.000,108.000,31.000,79.000,78.000,78.000,78.000,76.000,77.000,76.000,74.000,74.000,75.000,77.000,77.000,79.000,76.000,69.000,68.000,65.000,67.000,68.000,56.000,52.000,31.000,74.000,68.000,70.000,75.000,76.000,40.000}
-62.618 LMS_LASER_2D_RIGHT LMS2 ID=3974,time=1225719874.267487,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=63,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.608,18.363,15.230,12.614,10.936,9.820,8.936,8.087,7.414,6.842,6.279,5.902,5.511,5.184,4.863,4.596,4.348,4.100,3.902,3.721,3.553,3.386,3.222,3.094,2.954,2.798,2.714,2.633,2.538,2.420,2.414,2.320,2.248,2.157,2.113,2.053,1.993,1.953,1.902,1.858,1.813,1.759,1.716,1.679,1.653,1.624,1.576,1.549,1.524,1.516,1.475,1.459,1.414,1.383,1.373,1.338,1.322,1.304,1.286,1.278,1.270,1.267,1.253,1.267,1.276,1.290,1.300,1.296,1.283,1.262,1.246,1.246,1.213,1.197,1.185,1.149,1.141,1.132,1.107,1.083,1.086,1.092,1.096,1.086,1.082,1.077,1.069,1.058,1.031,1.043},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,36.000,29.000,119.000,104.000,80.000,63.000,58.000,57.000,56.000,61.000,66.000,66.000,68.000,70.000,70.000,71.000,72.000,73.000,74.000,76.000,78.000,78.000,79.000,79.000,79.000,81.000,80.000,80.000,79.000,79.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,75.000,78.000,78.000,71.000,72.000,74.000,74.000,75.000,75.000,75.000,78.000,78.000,78.000,78.000,79.000,78.000,74.000,67.000,56.000,46.000,43.000,40.000,34.000,33.000,32.000,43.000,51.000,52.000,43.000,40.000,42.000,34.000,29.000,27.000,28.000,31.000,37.000,37.000,42.000,44.000,44.000,34.000,30.000,36.000}
-62.619 DESIRED_THRUST iJoystick 84.5393230995
-62.619 DESIRED_RUDDER iJoystick 4.12305063021
-62.630 LMS_LASER_2D_LEFT LMS1 ID=4102,time=1225719874.275277,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=99,Range=[181]{1.034,1.033,1.050,1.047,1.063,1.064,1.076,1.086,1.094,1.111,1.126,1.131,1.133,1.151,1.161,1.173,1.188,1.202,1.216,1.225,1.233,1.255,1.265,1.278,1.295,1.307,1.325,1.339,1.364,1.379,1.398,1.416,1.441,1.465,1.486,1.497,1.530,1.561,1.575,1.602,1.625,1.663,1.689,1.725,1.770,1.793,1.842,1.864,1.907,1.961,2.006,2.034,2.084,2.134,2.185,2.228,2.281,2.346,2.396,2.469,2.521,2.587,2.667,2.746,2.787,2.788,2.792,2.881,3.009,3.078,3.177,3.294,3.408,3.518,3.638,3.775,3.931,4.097,4.122,4.111,4.122,4.166,4.177,4.188,4.194,4.188,4.205,4.208,4.186,4.216,4.266,4.287,4.288,4.306,4.324,4.314,4.326,4.330,4.328,4.329,4.329,4.329,4.338,4.354,4.344,4.351,4.358,4.354,4.363,4.367,4.385,4.383,4.392,4.403,4.406,4.418,4.433,4.440,4.448,4.461,4.479,3.375,3.575,2.495,2.544,2.473,2.485,2.486,2.513,2.553,2.577,2.602,2.631,2.705,2.961,2.852,4.697,2.761,2.833,2.773,2.913,2.975,2.849,2.912,2.877,2.763,2.881,3.064,3.027,3.068,3.080,2.975,3.049,5.076,5.105,5.127,5.150,5.190,5.218,5.246,5.278,5.320,5.348,5.381,5.418,5.457,5.489,5.517,5.518,5.553,5.594,5.558,5.602,5.855,6.630,5.479,5.431,5.447,5.428,5.445,5.448},Reflectance=[181]{43.000,43.000,43.000,46.000,37.000,46.000,43.000,44.000,44.000,39.000,39.000,45.000,47.000,43.000,43.000,46.000,44.000,43.000,41.000,46.000,46.000,44.000,49.000,47.000,45.000,51.000,48.000,50.000,49.000,52.000,52.000,53.000,53.000,52.000,54.000,55.000,54.000,52.000,55.000,55.000,58.000,55.000,54.000,55.000,51.000,57.000,55.000,56.000,56.000,53.000,54.000,56.000,48.000,47.000,46.000,50.000,49.000,39.000,41.000,38.000,46.000,48.000,45.000,46.000,52.000,53.000,51.000,49.000,57.000,49.000,52.000,46.000,46.000,46.000,47.000,46.000,46.000,65.000,76.000,70.000,68.000,73.000,75.000,75.000,75.000,75.000,75.000,73.000,67.000,68.000,73.000,76.000,76.000,78.000,79.000,79.000,79.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,80.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,13.000,105.000,46.000,99.000,76.000,77.000,77.000,75.000,76.000,78.000,77.000,78.000,85.000,85.000,35.000,78.000,31.000,92.000,74.000,116.000,117.000,39.000,115.000,92.000,66.000,70.000,96.000,101.000,101.000,119.000,56.000,40.000,77.000,78.000,77.000,76.000,75.000,76.000,74.000,72.000,74.000,75.000,76.000,76.000,77.000,76.000,72.000,67.000,67.000,66.000,69.000,60.000,55.000,32.000,71.000,67.000,34.000,64.000,62.000,69.000}
-62.643 DESIRED_THRUST iJoystick 83.5077974792
-62.643 DESIRED_RUDDER iJoystick 4.12305063021
-62.631 LMS_LASER_2D_RIGHT LMS2 ID=3975,time=1225719874.280821,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=64,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.635,20.105,15.769,12.897,11.107,9.935,9.037,8.176,7.489,6.906,6.357,5.962,5.604,5.211,4.917,4.639,4.411,4.150,3.919,3.743,3.589,3.406,3.251,3.131,2.979,2.839,2.734,2.630,2.565,2.479,2.416,2.328,2.256,2.184,2.123,2.070,2.002,1.959,1.910,1.866,1.822,1.767,1.723,1.690,1.663,1.635,1.589,1.553,1.536,1.516,1.482,1.456,1.431,1.396,1.366,1.344,1.320,1.303,1.286,1.277,1.266,1.262,1.268,1.275,1.267,1.287,1.301,1.294,1.284,1.273,1.265,1.241,1.213,1.202,1.192,1.155,1.137,1.137,1.138,1.091,1.105,1.103,1.092,1.088,1.091,1.088,1.078,1.070,1.060,1.034},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,39.000,4.000,118.000,113.000,82.000,64.000,57.000,58.000,54.000,61.000,65.000,65.000,67.000,70.000,70.000,72.000,72.000,72.000,73.000,77.000,78.000,78.000,78.000,79.000,79.000,80.000,81.000,79.000,79.000,81.000,81.000,80.000,80.000,80.000,81.000,80.000,80.000,79.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,72.000,76.000,79.000,78.000,72.000,72.000,72.000,74.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,76.000,68.000,64.000,60.000,49.000,43.000,41.000,34.000,38.000,47.000,52.000,59.000,58.000,46.000,37.000,40.000,39.000,37.000,27.000,31.000,32.000,33.000,37.000,41.000,45.000,42.000,39.000,36.000,32.000}
-62.642 LMS_LASER_2D_LEFT LMS1 ID=4103,time=1225719874.288614,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=100,Range=[181]{1.026,1.038,1.046,1.052,1.063,1.067,1.084,1.082,1.092,1.102,1.120,1.127,1.136,1.141,1.161,1.177,1.193,1.199,1.220,1.226,1.232,1.251,1.263,1.281,1.288,1.307,1.312,1.332,1.357,1.379,1.396,1.421,1.436,1.461,1.486,1.511,1.521,1.559,1.582,1.593,1.623,1.653,1.682,1.724,1.770,1.790,1.825,1.869,1.915,1.953,1.997,2.036,2.082,2.135,2.175,2.234,2.280,2.336,2.396,2.449,2.513,2.583,2.647,2.746,2.783,2.786,2.780,2.876,3.000,3.074,3.163,3.268,3.402,3.509,3.622,3.763,3.931,4.079,4.113,4.114,4.118,4.157,4.180,4.191,4.193,4.188,4.203,4.209,4.188,4.210,4.260,4.288,4.280,4.301,4.314,4.314,4.312,4.321,4.314,4.332,4.334,4.337,4.333,4.341,4.339,4.344,4.347,4.363,4.364,4.367,4.374,4.389,4.394,4.391,4.404,4.417,4.431,4.439,4.451,4.451,4.469,4.477,3.520,3.492,2.488,2.565,2.483,2.483,2.513,2.599,2.572,2.622,2.630,2.714,2.938,2.890,2.766,3.067,2.886,2.780,2.868,2.957,2.895,2.879,2.800,2.801,2.874,3.100,3.015,3.042,3.036,3.106,3.052,3.098,5.091,5.116,5.152,5.182,5.217,5.239,5.274,5.312,5.338,5.375,5.410,5.454,5.484,5.509,5.522,5.535,5.594,5.567,5.581,5.829,6.639,5.435,5.445,5.458,5.502,5.450,5.468},Reflectance=[181]{36.000,41.000,37.000,44.000,40.000,48.000,43.000,47.000,43.000,48.000,44.000,39.000,44.000,47.000,43.000,43.000,36.000,45.000,43.000,42.000,46.000,45.000,43.000,43.000,47.000,51.000,54.000,51.000,50.000,48.000,48.000,52.000,55.000,50.000,50.000,53.000,54.000,55.000,54.000,55.000,57.000,54.000,55.000,54.000,55.000,56.000,56.000,55.000,56.000,53.000,50.000,49.000,47.000,47.000,46.000,48.000,49.000,42.000,46.000,46.000,45.000,46.000,54.000,45.000,54.000,52.000,57.000,50.000,53.000,50.000,50.000,47.000,51.000,45.000,48.000,48.000,45.000,64.000,76.000,74.000,70.000,73.000,75.000,76.000,74.000,75.000,75.000,74.000,68.000,69.000,73.000,76.000,77.000,78.000,78.000,79.000,80.000,80.000,78.000,80.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,106.000,105.000,51.000,103.000,79.000,76.000,75.000,87.000,77.000,80.000,79.000,85.000,79.000,111.000,35.000,16.000,115.000,76.000,92.000,117.000,40.000,102.000,75.000,70.000,68.000,113.000,85.000,99.000,93.000,119.000,41.000,7.000,77.000,76.000,77.000,76.000,75.000,74.000,71.000,75.000,74.000,74.000,74.000,74.000,72.000,67.000,68.000,69.000,66.000,69.000,59.000,55.000,31.000,29.000,61.000,34.000,70.000,68.000,75.000}
-62.642 LMS_LASER_2D_RIGHT LMS2 ID=3976,time=1225719874.294153,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=65,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.914,-1.000,16.074,12.988,11.317,10.055,9.142,8.307,7.588,6.964,6.466,5.999,5.646,5.265,4.946,4.680,4.430,4.169,3.946,3.767,3.617,3.445,3.270,3.116,3.005,2.855,2.750,2.676,2.588,2.505,2.418,2.338,2.275,2.200,2.131,2.071,2.019,1.961,1.912,1.876,1.839,1.776,1.735,1.699,1.665,1.642,1.580,1.562,1.536,1.505,1.482,1.459,1.430,1.395,1.365,1.350,1.326,1.305,1.288,1.279,1.269,1.264,1.260,1.274,1.276,1.287,1.292,1.297,1.287,1.273,1.258,1.230,1.199,1.201,1.192,1.161,1.137,1.143,1.113,1.101,1.120,1.103,1.055,1.091,1.085,1.084,1.071,1.065,1.053,1.048},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,18.000,0.000,109.000,118.000,84.000,68.000,57.000,56.000,54.000,60.000,64.000,66.000,67.000,70.000,71.000,71.000,73.000,73.000,73.000,77.000,78.000,78.000,78.000,80.000,79.000,80.000,80.000,79.000,81.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,79.000,80.000,79.000,80.000,79.000,73.000,76.000,79.000,78.000,72.000,74.000,71.000,72.000,75.000,76.000,77.000,78.000,79.000,79.000,78.000,77.000,70.000,63.000,60.000,57.000,47.000,40.000,35.000,38.000,51.000,63.000,71.000,61.000,40.000,39.000,39.000,41.000,30.000,30.000,37.000,32.000,25.000,36.000,41.000,43.000,45.000,42.000,37.000,34.000}
-62.647 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.8683,19.1578,-0.8428},Vel=[3x1]{-0.8949,-0.7977,4.7436},Raw=[2x1]{20.8891,-0.8428},time=1225719874.29441761970520,Speed=1.19885517362227,Pitch=0.01794682987071,Roll=0.02243353733839,PitchDot=0.05159713587829,RollDot=-0.00114411040426
-62.647 ODOMETRY_POSE iPlatform Pose=[3x1]{4.8683,19.1578,-0.8425},Vel=[3x1]{-0.8949,-0.7977,-1.5397},Raw=[2x1]{20.8891,-0.8428},time=1225719874.2944,Speed=1.1989,Pitch=-0.0048,Roll=0.0283,PitchDot=0.0028,RollDot=0.0515
-62.667 DESIRED_THRUST iJoystick 83.5077974792
-62.667 DESIRED_RUDDER iJoystick 4.12305063021
-62.671 DB_CLIENTS MOOSDB#1 LMS2,LMS1,iCameraLadybug,iGPS,pLogStereo,iCameraBumbleBee,uWatchdog,iJoystick,pNav,pLogger,iRemote,iRelayBox,iPlatform,Antler{lisa2},Antler{lisa3},Antler{Monarch},Antler{lisa4},DBWebServer,
-62.658 LMS_LASER_2D_LEFT LMS1 ID=4104,time=1225719874.301955,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=101,Range=[181]{1.022,1.034,1.040,1.055,1.058,1.064,1.067,1.088,1.095,1.100,1.117,1.126,1.134,1.147,1.166,1.178,1.185,1.202,1.209,1.223,1.231,1.251,1.262,1.276,1.295,1.296,1.319,1.339,1.362,1.376,1.390,1.409,1.427,1.460,1.479,1.502,1.532,1.539,1.576,1.595,1.619,1.653,1.688,1.717,1.751,1.783,1.814,1.862,1.903,1.947,1.989,2.040,2.075,2.123,2.180,2.229,2.273,2.336,2.389,2.450,2.503,2.570,2.644,2.728,2.778,2.777,2.772,2.838,2.969,3.067,3.138,3.244,3.381,3.501,3.613,3.751,3.902,4.076,4.119,4.110,4.106,4.147,4.169,4.177,4.184,4.188,4.190,4.200,4.179,4.209,4.254,4.274,4.272,4.289,4.311,4.306,4.311,4.309,4.306,4.319,4.317,4.326,4.329,4.326,4.326,4.335,4.344,4.348,4.358,4.352,4.365,4.373,4.382,4.388,4.394,4.410,4.412,4.430,4.438,4.448,4.458,4.467,4.476,3.474,2.468,2.520,2.458,2.473,2.594,2.640,2.568,2.587,2.613,2.668,2.811,2.739,2.852,3.182,3.082,2.898,2.916,2.938,2.874,2.709,2.794,2.841,2.905,3.034,2.901,3.018,2.983,3.097,3.045,5.054,5.084,5.109,5.142,5.172,5.198,5.230,5.265,5.296,5.326,5.360,5.400,5.431,5.462,5.497,5.522,5.532,5.585,5.568,5.576,5.781,6.639,6.674,5.455,5.459,5.489,5.492,5.490},Reflectance=[181]{34.000,35.000,42.000,45.000,43.000,46.000,43.000,41.000,44.000,42.000,42.000,43.000,47.000,46.000,45.000,36.000,39.000,43.000,47.000,40.000,46.000,45.000,43.000,45.000,45.000,51.000,50.000,50.000,49.000,51.000,49.000,47.000,51.000,50.000,51.000,53.000,51.000,54.000,55.000,56.000,55.000,54.000,54.000,54.000,54.000,56.000,58.000,55.000,54.000,51.000,50.000,42.000,47.000,45.000,38.000,41.000,44.000,41.000,42.000,42.000,47.000,48.000,48.000,46.000,49.000,51.000,57.000,55.000,57.000,51.000,48.000,48.000,54.000,45.000,48.000,46.000,43.000,60.000,75.000,72.000,69.000,73.000,74.000,75.000,74.000,75.000,73.000,74.000,68.000,69.000,72.000,75.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,80.000,80.000,80.000,79.000,79.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,104.000,50.000,93.000,76.000,76.000,97.000,98.000,76.000,76.000,75.000,80.000,83.000,77.000,109.000,111.000,112.000,94.000,104.000,107.000,113.000,64.000,75.000,76.000,72.000,89.000,64.000,90.000,79.000,118.000,30.000,79.000,77.000,77.000,76.000,75.000,75.000,74.000,71.000,72.000,73.000,73.000,71.000,67.000,66.000,66.000,68.000,69.000,66.000,65.000,61.000,50.000,31.000,33.000,57.000,39.000,63.000,72.000,76.000}
-62.670 LMS_LASER_2D_LEFT LMS1 ID=4105,time=1225719874.315293,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=102,Range=[181]{1.012,1.042,1.043,1.055,1.058,1.067,1.080,1.084,1.092,1.098,1.107,1.119,1.136,1.143,1.162,1.173,1.181,1.195,1.208,1.225,1.233,1.251,1.263,1.264,1.288,1.303,1.322,1.335,1.346,1.373,1.393,1.405,1.434,1.459,1.482,1.497,1.521,1.540,1.573,1.591,1.618,1.653,1.672,1.712,1.753,1.781,1.809,1.862,1.902,1.952,1.985,2.039,2.079,2.124,2.166,2.212,2.262,2.321,2.365,2.409,2.500,2.567,2.639,2.725,2.778,2.775,2.778,2.835,2.959,3.057,3.138,3.231,3.352,3.485,3.606,3.738,3.904,4.077,4.108,4.106,4.097,4.141,4.164,4.179,4.185,4.176,4.187,4.196,4.166,4.193,4.237,4.267,4.273,4.276,4.310,4.313,4.307,4.306,4.307,4.312,4.314,4.323,4.317,4.328,4.326,4.326,4.335,4.348,4.353,4.350,4.363,4.373,4.377,4.385,4.393,4.403,4.403,4.420,4.442,4.448,4.458,4.469,4.476,3.493,2.551,2.474,2.454,2.465,2.585,2.584,2.549,2.547,2.576,2.659,2.681,2.688,2.752,2.925,3.139,2.949,2.792,2.777,2.673,2.729,2.863,2.817,2.884,2.899,2.889,3.075,3.113,2.994,5.021,5.050,5.077,5.101,5.135,5.160,5.192,5.228,5.254,5.295,5.321,5.357,5.391,5.429,5.454,5.503,5.516,5.527,5.576,5.568,5.562,5.740,6.648,6.670,5.441,5.452,5.547,5.513,5.486},Reflectance=[181]{32.000,39.000,39.000,37.000,43.000,39.000,41.000,36.000,43.000,45.000,45.000,48.000,44.000,43.000,40.000,41.000,46.000,44.000,45.000,46.000,45.000,42.000,43.000,49.000,51.000,46.000,51.000,49.000,49.000,49.000,47.000,52.000,50.000,50.000,52.000,55.000,54.000,55.000,54.000,54.000,55.000,54.000,55.000,56.000,55.000,55.000,56.000,55.000,54.000,49.000,49.000,45.000,40.000,45.000,50.000,46.000,48.000,43.000,55.000,55.000,46.000,42.000,41.000,41.000,49.000,51.000,56.000,54.000,50.000,47.000,48.000,46.000,53.000,48.000,49.000,44.000,45.000,60.000,75.000,74.000,69.000,71.000,75.000,75.000,75.000,74.000,72.000,72.000,66.000,67.000,72.000,75.000,77.000,76.000,77.000,78.000,79.000,78.000,79.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,79.000,79.000,80.000,79.000,79.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,79.000,78.000,106.000,105.000,82.000,78.000,76.000,97.000,83.000,75.000,75.000,75.000,78.000,80.000,76.000,79.000,80.000,96.000,93.000,72.000,75.000,66.000,72.000,94.000,77.000,74.000,68.000,60.000,106.000,118.000,21.000,77.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,73.000,72.000,72.000,72.000,71.000,67.000,65.000,68.000,66.000,67.000,66.000,64.000,58.000,47.000,29.000,34.000,36.000,41.000,70.000,68.000,75.000}
-62.670 LMS_LASER_2D_RIGHT LMS2 ID=3977,time=1225719874.307500,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=66,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.134,-1.000,16.272,13.228,11.469,10.142,9.210,8.394,7.634,7.020,6.528,6.051,5.680,5.292,4.990,4.698,4.457,4.203,3.966,3.784,3.612,3.471,3.268,3.124,3.024,2.865,2.737,2.684,2.587,2.488,2.415,2.346,2.267,2.211,2.139,2.078,2.024,1.959,1.918,1.885,1.841,1.785,1.732,1.701,1.672,1.653,1.586,1.563,1.533,1.502,1.475,1.458,1.429,1.396,1.365,1.351,1.320,1.305,1.292,1.285,1.272,1.263,1.255,1.259,1.276,1.287,1.291,1.286,1.286,1.270,1.241,1.232,1.217,1.193,1.195,1.166,1.138,1.144,1.138,1.137,1.128,1.119,1.064,1.060,1.083,1.081,1.071,1.068,1.053,1.029},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,13.000,0.000,106.000,119.000,84.000,69.000,57.000,56.000,55.000,59.000,64.000,66.000,67.000,69.000,70.000,71.000,73.000,74.000,74.000,77.000,77.000,78.000,80.000,80.000,79.000,78.000,76.000,79.000,80.000,81.000,80.000,81.000,81.000,81.000,80.000,80.000,79.000,79.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,79.000,78.000,77.000,78.000,77.000,79.000,79.000,75.000,73.000,75.000,76.000,75.000,76.000,77.000,78.000,77.000,77.000,74.000,67.000,56.000,49.000,47.000,48.000,44.000,40.000,56.000,60.000,61.000,57.000,47.000,38.000,37.000,41.000,37.000,40.000,37.000,36.000,25.000,27.000,38.000,46.000,45.000,44.000,37.000,31.000}
-62.682 LMS_LASER_2D_RIGHT LMS2 ID=3978,time=1225719874.320846,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=67,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.959,-1.000,16.281,13.264,11.552,10.177,9.247,8.420,7.662,7.038,6.545,6.071,5.681,5.336,5.016,4.706,4.475,4.221,3.977,3.793,3.621,3.471,3.309,3.150,3.024,2.870,2.770,2.687,2.597,2.507,2.425,2.346,2.275,2.203,2.130,2.071,2.019,1.976,1.925,1.886,1.841,1.785,1.740,1.710,1.671,1.652,1.602,1.567,1.519,1.477,1.473,1.462,1.419,1.387,1.363,1.350,1.320,1.305,1.301,1.289,1.275,1.265,1.256,1.259,1.265,1.285,1.286,1.271,1.271,1.256,1.229,1.227,1.215,1.194,1.191,1.148,1.136,1.138,1.134,1.098,1.107,1.112,1.069,1.052,1.043,1.084,1.073,1.069,1.060,1.025},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,13.000,0.000,106.000,119.000,86.000,70.000,58.000,56.000,55.000,59.000,64.000,66.000,68.000,68.000,70.000,70.000,73.000,73.000,75.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,75.000,80.000,81.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,79.000,79.000,81.000,80.000,79.000,79.000,80.000,79.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,75.000,74.000,75.000,76.000,75.000,76.000,77.000,76.000,78.000,77.000,75.000,68.000,63.000,52.000,52.000,61.000,57.000,54.000,62.000,61.000,56.000,54.000,49.000,32.000,35.000,40.000,33.000,27.000,31.000,35.000,25.000,25.000,27.000,43.000,42.000,37.000,36.000,30.000}
-62.684 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.8942,19.1809,-0.8459},Vel=[3x1]{-0.8603,-0.7620,0.1282},Raw=[2x1]{20.9239,-0.8459},time=1225719874.33121562004089,Speed=1.14920709091440,Pitch=0.01794682987071,Roll=0.02019018360455,PitchDot=0.05608384334597,RollDot=-0.00042623720943
-62.684 ODOMETRY_POSE iPlatform Pose=[3x1]{4.8942,19.1809,-0.8457},Vel=[3x1]{-0.8603,-0.7620,0.1284},Raw=[2x1]{20.9239,-0.8459},time=1225719874.3312,Speed=1.1492,Pitch=-0.0032,Roll=0.0268,PitchDot=0.0556,RollDot=-0.0076
-62.691 DESIRED_THRUST iJoystick 83.5077974792
-62.691 DESIRED_RUDDER iJoystick 4.12305063021
-62.311 RELAYBOX_STATUS iRelayBox LADYBUG is OFF,LMS1 is ON,LMS2 is ON,P10 is OFF,P11 is OFF,P12 is OFF,P13 is OFF,P14 is OFF,P15 is OFF,P16 is OFF,P5 is OFF,P6 is OFF,P7 is OFF,P8 is OFF,P9 is OFF,PANTILT is ON,
-62.682 LMS_LASER_2D_LEFT LMS1 ID=4106,time=1225719874.328631,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=103,Range=[181]{1.033,1.017,1.039,1.048,1.063,1.072,1.072,1.078,1.095,1.102,1.114,1.131,1.138,1.148,1.150,1.172,1.180,1.193,1.215,1.216,1.238,1.251,1.261,1.272,1.295,1.306,1.319,1.336,1.344,1.377,1.394,1.410,1.430,1.458,1.488,1.503,1.531,1.548,1.575,1.584,1.620,1.654,1.687,1.708,1.742,1.778,1.804,1.861,1.903,1.944,1.987,2.031,2.080,2.127,2.169,2.227,2.266,2.313,2.360,2.390,2.493,2.557,2.632,2.722,2.780,2.775,2.777,2.844,2.955,3.058,3.148,3.227,3.354,3.479,3.604,3.749,3.899,4.084,4.102,4.098,4.093,4.137,4.166,4.174,4.176,4.177,4.183,4.196,4.166,4.197,4.237,4.274,4.273,4.280,4.298,4.306,4.304,4.306,4.312,4.309,4.317,4.320,4.317,4.327,4.323,4.323,4.332,4.341,4.349,4.352,4.355,4.367,4.379,4.381,4.392,4.398,4.403,4.418,4.429,4.442,4.453,4.469,3.265,3.339,2.703,2.571,2.526,2.555,2.524,2.586,2.492,2.479,2.523,2.724,2.679,2.659,2.732,2.937,3.018,2.774,2.784,2.724,2.676,2.884,2.896,2.847,2.870,2.960,2.890,2.939,4.971,4.994,5.026,5.040,5.065,5.101,5.124,5.159,5.192,5.218,5.257,5.286,5.324,5.353,5.396,5.420,5.460,5.489,5.516,5.533,5.578,5.568,5.562,5.724,6.643,6.676,5.459,5.430,5.559,5.511,5.488},Reflectance=[181]{39.000,32.000,34.000,42.000,41.000,41.000,41.000,44.000,44.000,43.000,41.000,41.000,40.000,45.000,47.000,40.000,40.000,43.000,40.000,46.000,39.000,42.000,42.000,48.000,45.000,48.000,49.000,49.000,49.000,47.000,51.000,51.000,52.000,49.000,51.000,53.000,54.000,54.000,55.000,55.000,55.000,55.000,53.000,54.000,54.000,54.000,58.000,55.000,54.000,49.000,46.000,47.000,38.000,43.000,47.000,44.000,50.000,48.000,58.000,58.000,50.000,46.000,43.000,39.000,49.000,51.000,51.000,51.000,48.000,47.000,48.000,48.000,50.000,53.000,44.000,43.000,48.000,55.000,73.000,72.000,68.000,70.000,73.000,74.000,74.000,75.000,74.000,72.000,66.000,68.000,72.000,75.000,77.000,77.000,77.000,78.000,78.000,78.000,80.000,79.000,79.000,80.000,79.000,77.000,79.000,79.000,79.000,78.000,78.000,79.000,80.000,79.000,79.000,77.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,25.000,17.000,127.000,116.000,92.000,93.000,78.000,88.000,69.000,72.000,78.000,82.000,79.000,73.000,78.000,89.000,90.000,75.000,72.000,73.000,67.000,98.000,108.000,73.000,79.000,91.000,56.000,29.000,78.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,76.000,76.000,74.000,72.000,70.000,71.000,73.000,67.000,68.000,69.000,66.000,65.000,67.000,64.000,58.000,47.000,27.000,32.000,31.000,40.000,65.000,67.000,73.000}
-62.694 LMS_LASER_2D_LEFT LMS1 ID=4107,time=1225719874.341968,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=104,Range=[181]{1.031,1.029,1.047,1.054,1.055,1.064,1.080,1.080,1.092,1.095,1.111,1.124,1.141,1.156,1.157,1.170,1.187,1.193,1.207,1.221,1.238,1.237,1.259,1.268,1.287,1.306,1.314,1.334,1.355,1.371,1.393,1.408,1.429,1.453,1.479,1.503,1.517,1.539,1.565,1.589,1.618,1.651,1.671,1.711,1.742,1.772,1.815,1.860,1.896,1.945,1.989,2.040,2.079,2.118,2.179,2.226,2.257,2.304,2.358,2.387,2.497,2.566,2.632,2.724,2.774,2.774,2.773,2.848,2.970,3.052,3.131,3.224,3.330,3.457,3.611,3.738,3.912,4.062,4.101,4.095,4.097,4.134,4.157,4.179,4.180,4.172,4.178,4.188,4.166,4.188,4.237,4.275,4.273,4.278,4.304,4.294,4.304,4.295,4.312,4.307,4.311,4.320,4.317,4.327,4.323,4.326,4.335,4.335,4.347,4.342,4.349,4.367,4.376,4.383,4.398,4.400,4.404,4.422,4.430,4.439,4.448,3.372,3.326,3.416,3.584,2.488,2.630,2.603,2.520,2.630,2.658,2.505,2.558,2.723,2.696,2.675,2.777,2.985,2.866,2.773,2.796,2.782,2.701,2.853,2.882,2.941,2.952,2.879,3.025,2.925,4.970,4.994,5.022,5.040,5.066,5.099,5.127,5.160,5.182,5.228,5.251,5.284,5.309,5.353,5.385,5.414,5.458,5.496,5.515,5.533,5.576,5.568,5.550,5.712,6.632,6.667,5.451,5.416,5.549,5.526,5.469},Reflectance=[181]{42.000,38.000,41.000,40.000,38.000,41.000,41.000,45.000,43.000,44.000,44.000,42.000,41.000,41.000,45.000,44.000,44.000,43.000,46.000,44.000,44.000,48.000,46.000,46.000,47.000,48.000,47.000,52.000,50.000,49.000,47.000,50.000,51.000,51.000,51.000,53.000,56.000,54.000,58.000,57.000,55.000,57.000,54.000,56.000,54.000,55.000,55.000,54.000,55.000,54.000,47.000,42.000,40.000,39.000,43.000,44.000,54.000,48.000,60.000,57.000,43.000,46.000,43.000,40.000,50.000,50.000,54.000,49.000,47.000,52.000,48.000,45.000,47.000,48.000,47.000,48.000,53.000,57.000,72.000,71.000,66.000,72.000,73.000,75.000,75.000,75.000,72.000,73.000,66.000,68.000,72.000,75.000,77.000,76.000,78.000,78.000,78.000,78.000,80.000,79.000,78.000,78.000,79.000,77.000,79.000,79.000,79.000,79.000,80.000,79.000,78.000,79.000,78.000,75.000,77.000,78.000,79.000,79.000,78.000,78.000,79.000,107.000,96.000,107.000,107.000,36.000,124.000,105.000,75.000,96.000,97.000,73.000,78.000,84.000,80.000,72.000,88.000,91.000,78.000,74.000,73.000,90.000,57.000,51.000,85.000,94.000,96.000,75.000,114.000,25.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,75.000,72.000,69.000,71.000,72.000,67.000,70.000,70.000,66.000,61.000,65.000,63.000,62.000,50.000,22.000,32.000,36.000,36.000,66.000,74.000,68.000}
-62.694 LMS_LASER_2D_RIGHT LMS2 ID=3979,time=1225719874.334191,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=68,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.084,-1.000,16.347,13.194,11.582,10.195,9.307,8.466,7.671,7.005,6.513,6.052,5.690,5.318,5.024,4.699,4.466,4.221,3.995,3.840,3.622,3.481,3.318,3.138,3.005,2.844,2.786,2.696,2.605,2.499,2.425,2.330,2.276,2.213,2.121,2.062,2.029,1.977,1.916,1.885,1.832,1.779,1.743,1.717,1.681,1.642,1.608,1.562,1.524,1.496,1.470,1.448,1.417,1.396,1.366,1.334,1.326,1.312,1.293,1.288,1.274,1.263,1.263,1.252,1.265,1.281,1.288,1.277,1.249,1.256,1.239,1.223,1.218,1.201,1.190,1.164,1.130,1.129,1.135,1.094,1.122,1.112,1.067,1.062,1.056,1.083,1.075,1.066,1.053,1.036},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,18.000,0.000,106.000,120.000,85.000,70.000,58.000,56.000,55.000,57.000,65.000,66.000,67.000,69.000,70.000,71.000,72.000,74.000,75.000,76.000,77.000,78.000,79.000,79.000,79.000,79.000,77.000,80.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,77.000,72.000,75.000,78.000,75.000,76.000,75.000,74.000,75.000,74.000,74.000,76.000,78.000,79.000,77.000,77.000,77.000,72.000,64.000,54.000,49.000,60.000,67.000,58.000,59.000,60.000,57.000,53.000,49.000,40.000,34.000,35.000,33.000,27.000,34.000,35.000,26.000,27.000,29.000,38.000,43.000,41.000,40.000,32.000}
-62.707 LMS_LASER_2D_LEFT LMS1 ID=4108,time=1225719874.355303,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=105,Range=[181]{1.031,1.037,1.041,1.049,1.054,1.071,1.075,1.078,1.090,1.096,1.115,1.129,1.134,1.153,1.165,1.181,1.183,1.206,1.212,1.221,1.235,1.243,1.256,1.269,1.279,1.303,1.315,1.328,1.348,1.365,1.395,1.405,1.436,1.455,1.478,1.504,1.523,1.540,1.573,1.590,1.620,1.649,1.675,1.717,1.746,1.781,1.814,1.866,1.907,1.954,1.987,2.048,2.080,2.131,2.190,2.222,2.252,2.310,2.365,2.394,2.500,2.555,2.630,2.706,2.766,2.766,2.774,2.856,2.968,3.058,3.127,3.218,3.318,3.453,3.609,3.734,3.936,4.037,4.097,4.089,4.096,4.132,4.161,4.169,4.170,4.170,4.180,4.191,4.166,4.187,4.236,4.267,4.262,4.277,4.297,4.299,4.301,4.304,4.305,4.312,4.318,4.324,4.314,4.324,4.323,4.330,4.328,4.333,4.341,4.349,4.349,4.361,4.368,4.388,4.389,4.392,4.403,4.421,4.428,4.421,3.408,3.205,3.210,3.318,2.908,2.525,2.639,2.509,2.520,2.633,2.771,2.635,2.582,2.618,2.729,2.698,2.819,3.069,3.020,2.783,2.889,2.740,2.852,2.854,2.956,2.863,2.984,2.969,2.910,2.947,4.959,4.992,5.025,5.042,5.067,5.100,5.134,5.159,5.194,5.226,5.248,5.276,5.309,5.350,5.385,5.416,5.455,5.499,5.516,5.556,5.585,5.559,5.550,5.734,6.638,5.500,5.481,5.421,5.517,5.514,5.436},Reflectance=[181]{41.000,41.000,43.000,38.000,40.000,41.000,43.000,40.000,41.000,46.000,45.000,44.000,43.000,39.000,41.000,45.000,42.000,41.000,44.000,40.000,47.000,47.000,49.000,47.000,47.000,45.000,48.000,49.000,54.000,54.000,51.000,49.000,51.000,51.000,54.000,54.000,55.000,55.000,58.000,58.000,55.000,56.000,56.000,54.000,56.000,56.000,54.000,53.000,49.000,45.000,46.000,42.000,41.000,40.000,39.000,51.000,55.000,47.000,56.000,56.000,49.000,50.000,54.000,48.000,51.000,51.000,54.000,52.000,53.000,55.000,46.000,48.000,45.000,46.000,50.000,50.000,49.000,58.000,71.000,69.000,66.000,71.000,74.000,74.000,75.000,75.000,73.000,74.000,66.000,67.000,72.000,75.000,76.000,76.000,76.000,77.000,78.000,78.000,78.000,78.000,77.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,78.000,79.000,79.000,76.000,74.000,77.000,78.000,79.000,78.000,78.000,78.000,108.000,76.000,75.000,97.000,120.000,52.000,104.000,76.000,75.000,99.000,108.000,86.000,74.000,74.000,83.000,73.000,94.000,101.000,83.000,72.000,94.000,39.000,38.000,55.000,101.000,48.000,94.000,96.000,54.000,14.000,77.000,76.000,78.000,78.000,77.000,77.000,77.000,76.000,76.000,75.000,74.000,72.000,69.000,70.000,70.000,68.000,69.000,71.000,66.000,59.000,64.000,64.000,62.000,48.000,21.000,14.000,62.000,35.000,74.000,73.000,41.000}
-62.707 LMS_LASER_2D_RIGHT LMS2 ID=3980,time=1225719874.347535,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=69,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.993,-1.000,16.238,13.124,11.424,10.141,9.228,8.353,7.649,7.005,6.513,6.052,5.655,5.327,4.991,4.681,4.456,4.189,3.990,3.826,3.621,3.481,3.317,3.117,3.005,2.859,2.779,2.678,2.598,2.476,2.415,2.345,2.286,2.209,2.103,2.073,2.038,1.985,1.918,1.884,1.832,1.794,1.748,1.707,1.677,1.643,1.608,1.559,1.520,1.485,1.465,1.448,1.414,1.392,1.367,1.342,1.329,1.297,1.284,1.279,1.266,1.262,1.259,1.250,1.271,1.281,1.295,1.285,1.257,1.248,1.234,1.227,1.204,1.197,1.200,1.163,1.139,1.144,1.138,1.094,1.081,1.072,1.067,1.058,1.088,1.090,1.074,1.067,1.055,1.010},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,20.000,0.000,107.000,120.000,84.000,68.000,58.000,57.000,54.000,57.000,64.000,66.000,67.000,68.000,72.000,71.000,72.000,75.000,74.000,76.000,77.000,78.000,78.000,78.000,79.000,79.000,78.000,80.000,81.000,80.000,80.000,80.000,81.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,79.000,77.000,66.000,74.000,77.000,78.000,79.000,77.000,75.000,71.000,61.000,66.000,73.000,78.000,79.000,78.000,76.000,75.000,68.000,57.000,50.000,45.000,56.000,65.000,64.000,61.000,61.000,63.000,60.000,49.000,40.000,37.000,39.000,33.000,27.000,27.000,27.000,26.000,26.000,34.000,42.000,43.000,43.000,38.000,28.000}
-62.715 DESIRED_THRUST iJoystick 83.5077974792
-62.715 DESIRED_RUDDER iJoystick 4.12305063021
-62.719 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.9289,19.2115,-0.8494},Vel=[3x1]{-0.8717,-0.7667,0.1282},Raw=[2x1]{20.9702,-0.8494},time=1225719874.36647868156433,Speed=1.16088899272802,Pitch=0.02019018360455,Roll=0.02019018360455,PitchDot=0.06281390454748,RollDot=0.00069543965749
-62.719 ODOMETRY_POSE iPlatform Pose=[3x1]{4.9289,19.2115,-0.8492},Vel=[3x1]{-0.8717,-0.7667,0.1285},Raw=[2x1]{20.9702,-0.8494},time=1225719874.3665,Speed=1.1609,Pitch=-0.0018,Roll=0.0285,PitchDot=0.0624,RollDot=-0.0074
-61.932 CAMERA_FILE_WRITE iCameraLadybug time=1225719873.579,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.579-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.579-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.579-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.579-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.579-4.jpg
-62.707 LMS_LASER_2D_RIGHT LMS2 ID=3981,time=1225719874.360865,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=70,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.000,-1.000,16.017,12.969,11.273,10.038,9.119,8.290,7.570,6.982,6.496,6.007,5.630,5.300,4.981,4.646,4.429,4.194,3.955,3.773,3.595,3.461,3.286,3.082,2.991,2.883,2.778,2.670,2.566,2.455,2.397,2.327,2.274,2.194,2.093,2.066,2.029,1.977,1.925,1.866,1.830,1.793,1.759,1.693,1.665,1.642,1.612,1.554,1.527,1.480,1.466,1.440,1.408,1.380,1.365,1.348,1.330,1.308,1.289,1.278,1.266,1.255,1.253,1.257,1.269,1.280,1.287,1.273,1.249,1.249,1.237,1.225,1.208,1.197,1.201,1.180,1.146,1.138,1.137,1.093,1.095,1.099,1.069,1.056,1.083,1.076,1.069,1.054,1.053,1.006},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,0.000,107.000,116.000,84.000,67.000,59.000,56.000,54.000,59.000,65.000,67.000,68.000,69.000,70.000,70.000,72.000,74.000,73.000,76.000,77.000,78.000,77.000,75.000,80.000,81.000,78.000,80.000,79.000,74.000,80.000,80.000,80.000,81.000,79.000,81.000,81.000,80.000,79.000,80.000,79.000,79.000,79.000,78.000,77.000,79.000,78.000,73.000,77.000,78.000,79.000,79.000,77.000,77.000,75.000,68.000,69.000,74.000,77.000,78.000,78.000,77.000,73.000,65.000,56.000,50.000,45.000,54.000,66.000,59.000,58.000,60.000,61.000,56.000,49.000,48.000,40.000,45.000,37.000,28.000,28.000,30.000,25.000,26.000,38.000,41.000,42.000,40.000,35.000,26.000}
-62.718 LMS_LASER_2D_LEFT LMS1 ID=4109,time=1225719874.368637,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=106,Range=[181]{1.033,1.037,1.044,1.056,1.047,1.071,1.072,1.081,1.092,1.105,1.114,1.125,1.136,1.154,1.157,1.164,1.189,1.196,1.206,1.219,1.233,1.236,1.260,1.277,1.284,1.301,1.321,1.334,1.352,1.373,1.399,1.417,1.428,1.458,1.477,1.504,1.524,1.548,1.574,1.595,1.618,1.654,1.690,1.722,1.759,1.797,1.823,1.868,1.909,1.962,1.997,2.044,2.078,2.127,2.182,2.227,2.242,2.334,2.372,2.432,2.506,2.564,2.636,2.703,2.769,2.766,2.779,2.858,2.977,3.050,3.132,3.220,3.337,3.440,3.615,3.760,3.958,4.056,4.098,4.084,4.087,4.133,4.159,4.169,4.173,4.169,4.175,4.184,4.160,4.197,4.236,4.269,4.263,4.276,4.300,4.317,4.315,4.317,4.322,4.324,4.328,4.322,4.317,4.314,4.314,4.319,4.329,4.332,4.346,4.341,4.347,4.359,4.375,4.387,4.389,4.392,4.395,4.419,4.429,3.751,3.317,3.207,3.211,2.722,2.580,2.507,2.509,2.495,2.582,2.659,2.823,2.614,2.563,2.577,2.646,2.682,2.851,3.091,2.907,2.745,2.942,4.764,2.990,2.981,2.847,2.958,2.931,2.936,4.916,4.943,4.969,4.992,5.015,5.041,5.068,5.099,5.124,5.160,5.192,5.225,5.257,5.284,5.314,5.348,5.381,5.425,5.453,5.492,5.524,5.563,5.587,5.559,5.556,5.747,6.639,5.483,5.452,5.452,5.469,5.499,5.444},Reflectance=[181]{38.000,37.000,40.000,45.000,45.000,40.000,41.000,41.000,43.000,40.000,46.000,42.000,44.000,44.000,45.000,46.000,40.000,40.000,46.000,43.000,46.000,48.000,47.000,46.000,46.000,46.000,45.000,48.000,48.000,53.000,53.000,50.000,51.000,53.000,50.000,54.000,55.000,54.000,54.000,56.000,55.000,55.000,55.000,53.000,54.000,55.000,55.000,54.000,53.000,46.000,42.000,40.000,33.000,33.000,40.000,53.000,55.000,41.000,54.000,46.000,48.000,53.000,53.000,51.000,52.000,51.000,52.000,53.000,57.000,59.000,49.000,49.000,46.000,48.000,49.000,50.000,51.000,59.000,72.000,68.000,66.000,71.000,74.000,74.000,75.000,74.000,72.000,72.000,67.000,68.000,72.000,76.000,77.000,76.000,77.000,77.000,76.000,77.000,76.000,76.000,77.000,78.000,79.000,78.000,79.000,79.000,80.000,79.000,79.000,79.000,78.000,79.000,76.000,74.000,77.000,78.000,79.000,78.000,78.000,101.000,96.000,77.000,76.000,91.000,93.000,76.000,76.000,75.000,94.000,115.000,114.000,73.000,74.000,73.000,74.000,74.000,116.000,105.000,90.000,69.000,118.000,77.000,115.000,29.000,41.000,42.000,38.000,43.000,77.000,77.000,77.000,76.000,78.000,77.000,78.000,77.000,76.000,77.000,76.000,75.000,74.000,72.000,70.000,69.000,69.000,68.000,69.000,69.000,64.000,59.000,58.000,63.000,60.000,46.000,22.000,27.000,60.000,32.000,68.000,45.000,37.000}
-62.730 LMS_LASER_2D_LEFT LMS1 ID=4110,time=1225719874.381969,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=107,Range=[181]{1.034,1.032,1.049,1.046,1.048,1.065,1.067,1.081,1.090,1.110,1.118,1.132,1.140,1.151,1.155,1.166,1.185,1.202,1.211,1.226,1.235,1.258,1.260,1.278,1.287,1.307,1.325,1.337,1.362,1.376,1.397,1.410,1.434,1.458,1.483,1.504,1.530,1.556,1.574,1.599,1.618,1.662,1.700,1.732,1.761,1.797,1.831,1.873,1.918,1.956,2.001,2.054,2.102,2.143,2.198,2.233,2.251,2.342,2.385,2.446,2.511,2.535,2.641,2.704,2.771,2.762,2.775,2.845,2.982,3.061,3.133,3.212,3.337,3.438,3.643,3.767,3.960,4.063,4.098,4.079,4.090,4.136,4.161,4.170,4.170,4.166,4.174,4.180,4.163,4.193,4.246,4.267,4.251,4.289,4.291,4.315,4.326,4.317,4.326,4.327,4.322,4.315,4.319,4.321,4.315,4.323,4.328,4.335,4.344,4.342,4.347,4.357,4.371,4.380,4.391,4.392,4.403,4.418,4.421,4.439,3.427,3.218,3.210,2.584,2.502,2.514,2.511,2.537,2.632,2.742,2.735,2.625,2.537,2.554,2.628,2.664,2.807,2.970,2.748,2.759,2.804,2.856,2.897,4.801,2.924,2.925,4.871,3.061,4.917,4.944,4.968,4.994,5.023,5.043,5.066,5.109,5.133,5.158,5.192,5.223,5.254,5.283,5.317,5.349,5.387,5.425,5.457,5.497,5.530,5.553,5.598,5.559,5.566,5.762,6.642,5.627,5.454,5.419,5.454,5.512,5.448},Reflectance=[181]{39.000,38.000,36.000,46.000,47.000,42.000,43.000,46.000,46.000,43.000,43.000,35.000,45.000,43.000,46.000,46.000,43.000,43.000,43.000,47.000,47.000,45.000,42.000,42.000,47.000,48.000,48.000,50.000,52.000,51.000,52.000,54.000,54.000,53.000,52.000,54.000,54.000,54.000,54.000,54.000,55.000,54.000,51.000,50.000,55.000,55.000,50.000,49.000,53.000,51.000,40.000,41.000,36.000,38.000,39.000,43.000,55.000,40.000,48.000,48.000,54.000,63.000,55.000,51.000,53.000,53.000,55.000,55.000,52.000,56.000,49.000,49.000,46.000,51.000,53.000,58.000,51.000,58.000,72.000,66.000,67.000,72.000,74.000,75.000,75.000,73.000,71.000,70.000,68.000,67.000,72.000,75.000,76.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,75.000,78.000,78.000,79.000,78.000,78.000,78.000,93.000,78.000,75.000,91.000,74.000,75.000,77.000,82.000,98.000,115.000,101.000,73.000,74.000,69.000,74.000,74.000,92.000,80.000,72.000,68.000,52.000,16.000,33.000,78.000,19.000,29.000,78.000,22.000,77.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,76.000,76.000,76.000,75.000,73.000,69.000,71.000,70.000,67.000,68.000,70.000,66.000,60.000,54.000,58.000,63.000,60.000,45.000,22.000,68.000,61.000,40.000,66.000,15.000,37.000}
-62.730 LMS_LASER_2D_RIGHT LMS2 ID=3982,time=1225719874.374206,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=71,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.051,19.880,15.626,12.843,11.133,9.935,8.984,8.221,7.464,6.915,6.408,5.937,5.587,5.273,4.926,4.621,4.384,4.143,3.922,3.748,3.575,3.427,3.220,3.087,2.976,2.833,2.755,2.652,2.544,2.466,2.371,2.310,2.257,2.184,2.093,2.055,2.021,1.969,1.925,1.863,1.838,1.786,1.748,1.705,1.664,1.633,1.589,1.546,1.517,1.481,1.457,1.423,1.400,1.373,1.360,1.338,1.327,1.310,1.299,1.272,1.264,1.259,1.257,1.257,1.263,1.276,1.293,1.282,1.256,1.247,1.231,1.220,1.221,1.200,1.189,1.177,1.129,1.139,1.140,1.120,1.101,1.078,1.061,1.048,1.070,1.079,1.069,1.066,1.045,0.999},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,23.000,14.000,119.000,109.000,82.000,65.000,60.000,56.000,55.000,62.000,65.000,67.000,67.000,68.000,70.000,70.000,72.000,74.000,75.000,76.000,77.000,79.000,78.000,77.000,81.000,81.000,78.000,80.000,78.000,77.000,80.000,80.000,81.000,80.000,79.000,81.000,81.000,80.000,79.000,79.000,76.000,77.000,79.000,78.000,77.000,78.000,77.000,74.000,76.000,78.000,79.000,79.000,78.000,75.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,75.000,75.000,65.000,58.000,52.000,44.000,54.000,63.000,58.000,60.000,62.000,55.000,53.000,56.000,47.000,35.000,42.000,46.000,44.000,30.000,28.000,24.000,26.000,33.000,45.000,37.000,38.000,35.000,26.000}
-62.739 DESIRED_THRUST iJoystick 84.5393230995
-62.739 DESIRED_RUDDER iJoystick 4.12305063021
-62.744 LMS_LASER_2D_LEFT LMS1 ID=4111,time=1225719874.395302,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=108,Range=[181]{1.029,1.032,1.040,1.050,1.062,1.071,1.082,1.092,1.097,1.107,1.127,1.129,1.142,1.151,1.163,1.174,1.191,1.202,1.213,1.223,1.233,1.253,1.260,1.275,1.289,1.307,1.329,1.346,1.358,1.383,1.394,1.418,1.439,1.452,1.478,1.503,1.521,1.565,1.581,1.600,1.627,1.663,1.702,1.741,1.760,1.804,1.841,1.884,1.915,1.970,2.008,2.050,2.098,2.134,2.202,2.243,2.280,2.324,2.399,2.457,2.523,2.527,2.654,2.743,2.766,2.759,2.771,2.850,3.000,3.089,3.158,3.225,3.358,3.508,3.649,3.798,3.968,4.070,4.083,4.079,4.097,4.137,4.161,4.170,4.169,4.167,4.186,4.171,4.160,4.206,4.247,4.268,4.251,4.280,4.294,4.299,4.310,4.328,4.327,4.330,4.319,4.315,4.330,4.319,4.315,4.317,4.326,4.335,4.332,4.338,4.356,4.357,4.378,4.389,4.392,4.391,4.403,4.421,4.429,3.609,3.309,3.178,2.687,2.517,2.514,2.526,2.602,2.809,2.625,2.522,2.550,2.585,2.565,2.585,2.619,2.686,2.832,2.847,2.727,2.843,2.802,4.756,4.783,4.809,2.939,4.852,3.112,4.900,4.919,4.942,4.973,5.001,5.025,5.050,5.077,5.109,5.132,5.158,5.190,5.233,5.252,5.280,5.320,5.355,5.386,5.432,5.466,5.498,5.539,5.561,5.598,5.550,5.576,5.801,6.657,5.582,5.453,5.450,5.472,5.492,5.456},Reflectance=[181]{40.000,42.000,42.000,43.000,40.000,41.000,38.000,43.000,45.000,42.000,39.000,40.000,38.000,43.000,44.000,46.000,45.000,43.000,44.000,46.000,45.000,43.000,47.000,50.000,48.000,48.000,46.000,46.000,51.000,50.000,51.000,51.000,52.000,54.000,54.000,53.000,54.000,54.000,53.000,55.000,55.000,55.000,51.000,54.000,54.000,54.000,51.000,50.000,55.000,50.000,43.000,35.000,41.000,51.000,40.000,43.000,49.000,49.000,42.000,45.000,56.000,66.000,49.000,49.000,51.000,56.000,57.000,58.000,49.000,50.000,48.000,51.000,48.000,54.000,48.000,48.000,51.000,57.000,70.000,65.000,66.000,72.000,74.000,75.000,74.000,71.000,72.000,70.000,67.000,68.000,72.000,76.000,76.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,76.000,75.000,78.000,78.000,79.000,78.000,78.000,104.000,97.000,76.000,92.000,79.000,75.000,76.000,96.000,93.000,92.000,78.000,75.000,75.000,72.000,75.000,75.000,75.000,89.000,78.000,69.000,86.000,32.000,78.000,78.000,78.000,26.000,78.000,14.000,77.000,78.000,77.000,76.000,76.000,78.000,77.000,78.000,77.000,76.000,76.000,75.000,75.000,70.000,68.000,69.000,69.000,67.000,70.000,70.000,65.000,59.000,47.000,58.000,65.000,63.000,47.000,25.000,68.000,66.000,47.000,61.000,29.000,34.000}
-62.744 LMS_LASER_2D_RIGHT LMS2 ID=3983,time=1225719874.387547,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=72,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.704,18.436,15.316,12.658,10.846,9.793,8.876,8.075,7.351,6.854,6.357,5.894,5.536,5.237,4.863,4.571,4.367,4.137,3.895,3.733,3.540,3.407,3.190,3.066,2.966,2.796,2.709,2.652,2.560,2.466,2.398,2.303,2.248,2.183,2.095,2.046,2.002,1.954,1.907,1.858,1.819,1.756,1.740,1.695,1.628,1.612,1.564,1.551,1.524,1.485,1.440,1.423,1.397,1.369,1.351,1.336,1.317,1.303,1.290,1.274,1.255,1.253,1.244,1.265,1.263,1.277,1.291,1.291,1.273,1.254,1.243,1.232,1.221,1.201,1.178,1.173,1.144,1.139,1.129,1.095,1.080,1.064,1.061,1.050,1.075,1.074,1.058,1.053,1.028,1.003},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,35.000,30.000,116.000,104.000,84.000,63.000,59.000,56.000,54.000,63.000,66.000,67.000,68.000,68.000,70.000,72.000,72.000,75.000,74.000,77.000,77.000,78.000,78.000,78.000,80.000,80.000,76.000,80.000,80.000,79.000,80.000,81.000,81.000,80.000,80.000,81.000,80.000,80.000,79.000,80.000,78.000,70.000,79.000,78.000,75.000,75.000,77.000,78.000,78.000,77.000,76.000,76.000,74.000,73.000,77.000,77.000,77.000,75.000,77.000,77.000,74.000,76.000,74.000,64.000,57.000,52.000,43.000,38.000,50.000,58.000,57.000,56.000,51.000,49.000,55.000,49.000,39.000,37.000,32.000,28.000,28.000,27.000,24.000,28.000,34.000,41.000,41.000,39.000,30.000,24.000}
-62.744 LMS_LASER_2D_RIGHT LMS2 ID=3984,time=1225719874.400874,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=73,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.015,17.968,14.852,12.410,10.738,9.674,8.834,7.948,7.271,6.759,6.245,5.831,5.477,5.173,4.828,4.544,4.339,4.084,3.863,3.702,3.504,3.351,3.182,3.068,2.949,2.816,2.696,2.633,2.553,2.452,2.383,2.301,2.237,2.172,2.095,2.046,1.986,1.940,1.895,1.850,1.815,1.749,1.719,1.662,1.598,1.588,1.561,1.541,1.507,1.457,1.431,1.418,1.396,1.373,1.351,1.335,1.316,1.295,1.285,1.277,1.265,1.250,1.244,1.250,1.266,1.278,1.290,1.283,1.255,1.247,1.230,1.221,1.213,1.193,1.179,1.157,1.136,1.137,1.120,1.109,1.093,1.063,1.061,1.042,1.038,1.070,1.061,1.054,1.019,1.001},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,16.000,52.000,114.000,99.000,80.000,62.000,56.000,58.000,57.000,63.000,66.000,66.000,68.000,67.000,70.000,72.000,72.000,74.000,75.000,78.000,77.000,78.000,78.000,79.000,80.000,76.000,77.000,80.000,81.000,81.000,81.000,80.000,80.000,79.000,80.000,81.000,80.000,79.000,78.000,80.000,77.000,79.000,80.000,77.000,73.000,76.000,78.000,78.000,76.000,73.000,73.000,78.000,79.000,78.000,77.000,77.000,77.000,75.000,78.000,78.000,77.000,76.000,74.000,68.000,59.000,49.000,42.000,51.000,62.000,63.000,63.000,63.000,55.000,50.000,51.000,38.000,41.000,44.000,32.000,31.000,30.000,28.000,25.000,26.000,27.000,35.000,37.000,40.000,28.000,25.000}
-62.755 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.9635,19.2418,-0.8519},Vel=[3x1]{-0.8692,-0.7607,-3.0769},Raw=[2x1]{21.0161,-0.8519},time=1225719874.40236663818359,Speed=1.15504804182121,Pitch=0.02243353733839,Roll=0.02243353733839,PitchDot=0.05608384334597,RollDot=0.00085247441886
-62.755 ODOMETRY_POSE iPlatform Pose=[3x1]{4.9635,19.2418,-0.8516},Vel=[3x1]{-0.8692,-0.7607,-3.0768},Raw=[2x1]{21.0161,-0.8519},time=1225719874.4024,Speed=1.1550,Pitch=-0.0021,Roll=0.0317,PitchDot=-0.0560,RollDot=0.0028
-62.758 LMS_LASER_2D_LEFT LMS1 ID=4112,time=1225719874.408636,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=109,Range=[181]{1.033,1.039,1.047,1.050,1.063,1.067,1.083,1.096,1.098,1.111,1.123,1.131,1.140,1.166,1.173,1.181,1.191,1.209,1.213,1.220,1.242,1.250,1.265,1.286,1.297,1.312,1.325,1.341,1.361,1.381,1.393,1.417,1.443,1.470,1.489,1.512,1.539,1.566,1.593,1.609,1.644,1.672,1.712,1.742,1.769,1.812,1.847,1.892,1.932,1.951,2.016,2.059,2.107,2.160,2.204,2.239,2.299,2.355,2.398,2.468,2.532,2.526,2.657,2.754,2.766,2.748,2.786,2.900,2.990,3.101,3.164,3.227,3.375,3.531,3.651,3.830,3.984,4.089,4.084,4.079,4.111,4.137,4.162,4.168,4.170,4.161,4.182,4.167,4.166,4.209,4.245,4.268,4.251,4.284,4.292,4.304,4.313,4.330,4.322,4.319,4.320,4.314,4.311,4.319,4.309,4.322,4.323,4.330,4.332,4.346,4.355,4.366,4.374,4.381,4.382,4.399,4.402,4.417,3.690,3.416,3.243,3.020,2.590,2.517,2.527,2.633,2.820,2.650,2.496,2.510,2.529,2.567,2.626,2.682,2.661,2.726,2.802,2.836,2.776,2.885,2.845,4.767,4.781,4.808,4.835,4.850,4.878,4.903,4.916,4.948,4.972,5.001,5.024,5.051,5.076,5.107,5.134,5.167,5.198,5.229,5.255,5.283,5.324,5.357,5.402,5.439,5.461,5.498,5.533,5.578,5.588,5.542,5.598,5.839,6.661,5.515,5.461,5.457,5.493,5.496,5.440},Reflectance=[181]{43.000,46.000,45.000,43.000,41.000,43.000,38.000,40.000,45.000,44.000,41.000,46.000,45.000,42.000,45.000,40.000,42.000,42.000,40.000,48.000,45.000,46.000,44.000,45.000,43.000,46.000,48.000,47.000,48.000,49.000,50.000,54.000,50.000,54.000,51.000,54.000,54.000,54.000,55.000,55.000,54.000,55.000,48.000,54.000,54.000,53.000,53.000,49.000,52.000,52.000,43.000,32.000,34.000,41.000,42.000,50.000,40.000,43.000,42.000,45.000,55.000,66.000,46.000,49.000,51.000,55.000,56.000,57.000,56.000,47.000,47.000,51.000,47.000,55.000,49.000,43.000,43.000,58.000,68.000,64.000,68.000,72.000,75.000,74.000,75.000,72.000,74.000,69.000,66.000,69.000,72.000,76.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,80.000,79.000,78.000,78.000,78.000,75.000,77.000,78.000,77.000,78.000,77.000,102.000,92.000,75.000,81.000,87.000,76.000,76.000,115.000,119.000,85.000,72.000,74.000,75.000,75.000,80.000,81.000,76.000,74.000,75.000,77.000,72.000,99.000,21.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,76.000,76.000,76.000,78.000,78.000,77.000,76.000,77.000,76.000,75.000,74.000,66.000,69.000,68.000,67.000,69.000,72.000,68.000,64.000,53.000,47.000,59.000,65.000,58.000,48.000,27.000,66.000,60.000,44.000,70.000,33.000,32.000}
-62.763 DESIRED_THRUST iJoystick 84.5393230995
-62.763 DESIRED_RUDDER iJoystick 4.12305063021
-62.770 LMS_LASER_2D_RIGHT LMS2 ID=3985,time=1225719874.414215,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=74,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.211,14.240,12.018,10.512,9.525,8.646,7.808,7.195,6.687,6.163,5.794,5.424,5.112,4.808,4.526,4.313,3.983,3.853,3.653,3.497,3.314,3.164,3.050,2.903,2.792,2.679,2.614,2.525,2.452,2.374,2.309,2.216,2.148,2.086,2.036,1.977,1.924,1.875,1.830,1.786,1.745,1.725,1.647,1.583,1.579,1.560,1.527,1.482,1.455,1.430,1.411,1.378,1.369,1.343,1.324,1.315,1.299,1.285,1.276,1.261,1.244,1.244,1.255,1.269,1.279,1.277,1.260,1.239,1.231,1.224,1.208,1.213,1.201,1.189,1.149,1.143,1.137,1.134,1.114,1.072,1.064,1.048,1.083,1.075,1.065,1.027,1.012,1.010,0.998},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,77.000,116.000,93.000,75.000,60.000,58.000,57.000,57.000,63.000,67.000,66.000,68.000,69.000,70.000,71.000,73.000,74.000,74.000,76.000,78.000,78.000,78.000,79.000,79.000,79.000,80.000,80.000,81.000,81.000,81.000,80.000,79.000,78.000,80.000,80.000,80.000,79.000,80.000,79.000,79.000,81.000,80.000,77.000,77.000,78.000,78.000,77.000,71.000,69.000,72.000,76.000,76.000,77.000,74.000,73.000,76.000,77.000,78.000,78.000,76.000,76.000,74.000,62.000,52.000,45.000,48.000,60.000,64.000,64.000,68.000,70.000,59.000,50.000,35.000,35.000,43.000,44.000,36.000,32.000,27.000,27.000,27.000,41.000,43.000,38.000,28.000,25.000,24.000,24.000}
-62.783 DESIRED_THRUST iJoystick 84.5393230995
-62.783 DESIRED_RUDDER iJoystick 4.12305063021
-62.770 LMS_LASER_2D_LEFT LMS1 ID=4113,time=1225719874.421968,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=110,Range=[181]{1.034,1.040,1.045,1.052,1.063,1.076,1.082,1.090,1.102,1.115,1.128,1.136,1.142,1.155,1.173,1.182,1.188,1.215,1.217,1.226,1.236,1.249,1.266,1.282,1.294,1.320,1.332,1.349,1.368,1.383,1.400,1.419,1.445,1.472,1.496,1.526,1.538,1.566,1.592,1.626,1.643,1.691,1.733,1.748,1.793,1.822,1.849,1.891,1.947,1.986,2.026,2.071,2.115,2.168,2.217,2.263,2.307,2.369,2.421,2.482,2.539,2.535,2.648,2.758,2.761,2.759,2.817,2.890,3.005,3.115,3.184,3.248,3.414,3.542,3.680,3.835,3.990,4.097,4.088,4.088,4.106,4.146,4.161,4.165,4.162,4.166,4.182,4.163,4.168,4.222,4.249,4.260,4.259,4.293,4.292,4.300,4.312,4.319,4.321,4.318,4.320,4.323,4.315,4.317,4.319,4.323,4.323,4.333,4.333,4.341,4.358,4.360,4.376,4.372,4.386,4.397,4.410,4.417,3.509,3.382,3.306,3.222,2.657,2.619,2.668,3.157,3.363,2.682,2.584,2.518,2.552,2.603,2.700,2.767,2.680,2.713,2.852,2.893,2.835,2.936,2.866,4.774,4.793,4.809,4.833,4.854,4.877,4.902,4.925,4.956,4.974,5.002,5.032,5.058,5.083,5.108,5.144,5.174,5.208,5.235,5.261,5.289,5.330,5.366,5.409,5.445,5.466,5.507,5.537,5.585,5.577,5.542,5.622,5.919,5.448,5.454,5.453,5.446,5.529,5.464,5.407},Reflectance=[181]{39.000,47.000,46.000,44.000,45.000,43.000,47.000,45.000,43.000,45.000,44.000,39.000,47.000,46.000,37.000,45.000,44.000,37.000,41.000,47.000,48.000,49.000,46.000,49.000,50.000,46.000,47.000,47.000,47.000,50.000,53.000,51.000,51.000,51.000,54.000,52.000,54.000,54.000,54.000,54.000,54.000,51.000,45.000,49.000,53.000,54.000,54.000,53.000,47.000,45.000,44.000,37.000,34.000,35.000,39.000,44.000,40.000,45.000,44.000,49.000,54.000,69.000,50.000,51.000,52.000,55.000,54.000,52.000,55.000,49.000,48.000,49.000,49.000,52.000,46.000,43.000,43.000,57.000,64.000,62.000,69.000,72.000,74.000,73.000,75.000,73.000,74.000,68.000,67.000,70.000,73.000,76.000,76.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,76.000,76.000,77.000,76.000,77.000,78.000,77.000,105.000,90.000,75.000,79.000,88.000,95.000,114.000,25.000,99.000,83.000,88.000,74.000,76.000,75.000,83.000,81.000,74.000,75.000,74.000,74.000,72.000,105.000,20.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,76.000,76.000,76.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,73.000,68.000,68.000,67.000,67.000,71.000,71.000,67.000,64.000,44.000,53.000,58.000,64.000,58.000,48.000,21.000,63.000,61.000,40.000,75.000,27.000,36.000}
-62.782 LMS_LASER_2D_RIGHT LMS2 ID=3986,time=1225719874.427553,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=75,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.012,-1.000,16.674,13.493,11.651,10.313,9.405,8.539,7.725,7.102,6.580,6.071,5.697,5.363,5.059,4.740,4.474,4.247,3.973,3.819,3.589,3.452,3.266,3.126,3.034,2.855,2.761,2.679,2.595,2.491,2.434,2.362,2.283,2.202,2.144,2.078,2.019,1.970,1.916,1.858,1.812,1.779,1.752,1.716,1.631,1.589,1.580,1.542,1.507,1.471,1.439,1.422,1.404,1.387,1.372,1.341,1.308,1.297,1.294,1.274,1.259,1.246,1.237,1.235,1.255,1.269,1.275,1.269,1.248,1.232,1.223,1.230,1.207,1.209,1.206,1.178,1.153,1.134,1.133,1.104,1.089,1.095,1.079,1.067,1.075,1.045,1.027,1.034,1.031,1.007,1.010},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,7.000,0.000,93.000,124.000,88.000,73.000,57.000,57.000,56.000,59.000,64.000,67.000,67.000,68.000,70.000,71.000,71.000,74.000,74.000,74.000,75.000,78.000,77.000,75.000,79.000,80.000,80.000,80.000,80.000,79.000,81.000,80.000,80.000,81.000,79.000,80.000,80.000,80.000,79.000,80.000,79.000,80.000,80.000,79.000,78.000,79.000,79.000,76.000,70.000,67.000,72.000,76.000,72.000,72.000,77.000,76.000,74.000,74.000,75.000,77.000,78.000,77.000,74.000,71.000,62.000,53.000,44.000,56.000,65.000,67.000,67.000,63.000,69.000,57.000,48.000,34.000,36.000,43.000,43.000,30.000,29.000,32.000,30.000,29.000,33.000,29.000,28.000,30.000,31.000,24.000,21.000}
-62.791 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{4.9891,19.2642,-0.8529},Vel=[3x1]{-0.8689,-0.7588,0.1282},Raw=[2x1]{21.0501,-0.8529},time=1225719874.43862676620483,Speed=1.15358780409451,Pitch=0.02467689107222,Roll=0.02467689107222,PitchDot=0.02243353733839,RollDot=0.00085247441886
-62.791 ODOMETRY_POSE iPlatform Pose=[3x1]{4.9891,19.2642,-0.8526},Vel=[3x1]{-0.8689,-0.7588,0.1282},Raw=[2x1]{21.0501,-0.8529},time=1225719874.4386,Speed=1.1536,Pitch=-0.0023,Roll=0.0348,PitchDot=0.0224,RollDot=-0.0020
-62.794 LMS_LASER_2D_RIGHT LMS2 ID=3987,time=1225719874.440891,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=76,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.862,-1.000,16.196,13.115,11.258,10.082,9.176,8.325,7.511,6.986,6.512,5.991,5.646,5.310,4.990,4.689,4.421,4.194,3.948,3.760,3.537,3.406,3.238,3.108,3.001,2.850,2.732,2.662,2.584,2.502,2.426,2.344,2.239,2.179,2.139,2.059,2.011,1.961,1.898,1.850,1.813,1.781,1.743,1.688,1.633,1.606,1.583,1.532,1.481,1.457,1.435,1.402,1.385,1.372,1.364,1.345,1.312,1.289,1.272,1.262,1.257,1.235,1.243,1.239,1.262,1.267,1.286,1.272,1.252,1.240,1.218,1.221,1.207,1.204,1.194,1.176,1.142,1.126,1.125,1.132,1.116,1.106,1.082,1.067,1.085,1.066,1.033,1.033,1.038,0.998,1.004},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,18.000,0.000,109.000,119.000,85.000,70.000,57.000,56.000,56.000,61.000,64.000,68.000,67.000,69.000,70.000,71.000,72.000,74.000,74.000,75.000,76.000,78.000,76.000,75.000,81.000,81.000,80.000,81.000,79.000,79.000,81.000,80.000,81.000,82.000,80.000,79.000,80.000,80.000,79.000,80.000,79.000,81.000,80.000,79.000,78.000,79.000,77.000,67.000,70.000,73.000,75.000,75.000,76.000,77.000,78.000,77.000,75.000,73.000,74.000,76.000,78.000,76.000,72.000,64.000,53.000,41.000,42.000,46.000,61.000,60.000,57.000,58.000,60.000,55.000,51.000,41.000,38.000,41.000,41.000,35.000,50.000,49.000,30.000,31.000,43.000,34.000,28.000,29.000,32.000,24.000,23.000}
-62.807 DESIRED_THRUST iJoystick 84.5393230995
-62.807 DESIRED_RUDDER iJoystick 3.09152500992
-62.794 LMS_LASER_2D_LEFT LMS1 ID=4114,time=1225719874.435311,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=111,Range=[181]{1.033,1.029,1.031,1.058,1.063,1.081,1.086,1.092,1.107,1.120,1.116,1.140,1.146,1.147,1.172,1.182,1.191,1.208,1.217,1.225,1.246,1.257,1.275,1.289,1.298,1.319,1.327,1.348,1.372,1.399,1.411,1.427,1.453,1.475,1.501,1.529,1.550,1.572,1.590,1.623,1.657,1.696,1.728,1.760,1.796,1.822,1.861,1.895,1.950,1.987,2.038,2.073,2.126,2.160,2.219,2.266,2.319,2.362,2.431,2.489,2.541,2.606,2.697,2.759,2.759,2.767,2.830,2.904,3.016,3.131,3.195,3.276,3.426,3.568,3.698,3.827,4.003,4.088,4.088,4.088,4.121,4.148,4.161,4.158,4.164,4.166,4.177,4.160,4.177,4.226,4.249,4.253,4.258,4.290,4.292,4.292,4.299,4.318,4.313,4.316,4.314,4.314,4.323,4.323,4.314,4.326,4.323,4.326,4.333,4.342,4.348,4.357,4.369,4.378,4.380,4.401,4.409,4.417,3.339,3.409,3.299,3.286,3.263,3.310,3.324,3.333,3.288,3.244,2.652,2.607,2.604,2.615,2.686,2.683,2.678,2.749,2.818,2.840,2.764,2.760,2.782,2.837,4.789,4.813,4.832,4.859,4.887,4.912,4.933,4.954,4.982,5.002,5.029,5.065,5.083,5.114,5.143,5.174,5.208,5.235,5.266,5.301,5.334,5.379,5.418,5.450,5.465,5.507,5.522,5.593,5.571,5.549,5.668,5.821,5.495,5.428,5.447,5.463,5.531,5.429,5.445},Reflectance=[181]{43.000,49.000,47.000,43.000,46.000,45.000,44.000,43.000,42.000,44.000,47.000,45.000,44.000,50.000,46.000,45.000,42.000,42.000,42.000,50.000,43.000,46.000,46.000,48.000,48.000,46.000,49.000,46.000,44.000,46.000,51.000,51.000,51.000,52.000,52.000,53.000,55.000,57.000,58.000,53.000,52.000,49.000,52.000,46.000,50.000,54.000,55.000,55.000,49.000,49.000,41.000,42.000,38.000,47.000,40.000,41.000,42.000,47.000,45.000,55.000,51.000,51.000,51.000,51.000,51.000,51.000,49.000,51.000,55.000,48.000,49.000,50.000,50.000,48.000,46.000,43.000,44.000,57.000,62.000,63.000,70.000,73.000,74.000,73.000,75.000,73.000,72.000,67.000,67.000,71.000,73.000,76.000,75.000,77.000,78.000,78.000,77.000,77.000,78.000,76.000,78.000,79.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,76.000,76.000,76.000,75.000,75.000,78.000,77.000,19.000,101.000,80.000,79.000,78.000,98.000,111.000,111.000,94.000,85.000,100.000,80.000,73.000,76.000,81.000,75.000,73.000,75.000,70.000,73.000,67.000,52.000,28.000,17.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,75.000,76.000,76.000,76.000,77.000,77.000,76.000,77.000,76.000,75.000,70.000,69.000,69.000,68.000,68.000,74.000,72.000,67.000,64.000,41.000,60.000,59.000,61.000,55.000,7.000,68.000,65.000,50.000,63.000,76.000,35.000,71.000}
-62.807 LMS_LASER_2D_LEFT LMS1 ID=4115,time=1225719874.448653,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=112,Range=[181]{1.030,1.041,1.052,1.056,1.068,1.079,1.090,1.100,1.107,1.110,1.128,1.134,1.149,1.159,1.169,1.177,1.199,1.212,1.218,1.222,1.249,1.264,1.269,1.295,1.305,1.326,1.337,1.365,1.378,1.391,1.421,1.436,1.453,1.477,1.503,1.530,1.547,1.573,1.609,1.640,1.676,1.709,1.739,1.761,1.805,1.822,1.867,1.888,1.953,2.002,2.048,2.082,2.141,2.178,2.216,2.281,2.327,2.381,2.445,2.502,2.575,2.644,2.721,2.760,2.759,2.781,2.866,2.940,3.056,3.147,3.224,3.311,3.448,3.595,3.729,3.878,4.027,4.099,4.088,4.088,4.123,4.147,4.161,4.160,4.165,4.173,4.169,4.155,4.189,4.226,4.263,4.253,4.267,4.288,4.292,4.293,4.301,4.319,4.321,4.310,4.313,4.314,4.322,4.314,4.315,4.315,4.324,4.332,4.335,4.342,4.352,4.365,4.371,4.383,4.386,4.395,4.408,4.417,4.419,3.346,3.255,3.280,3.345,3.444,4.493,4.510,2.933,2.845,2.819,2.589,2.592,2.613,2.655,2.660,2.708,2.805,2.807,2.796,2.841,2.758,2.690,4.774,4.789,4.813,4.843,4.868,4.893,4.910,4.936,4.957,4.985,5.015,5.040,5.065,5.090,5.124,5.151,5.181,5.214,5.244,5.277,5.314,5.343,5.399,5.429,5.459,5.475,5.516,5.546,5.591,5.559,5.546,5.722,5.468,5.457,5.410,5.414,5.468,5.425,5.491,5.401},Reflectance=[181]{46.000,43.000,44.000,45.000,39.000,40.000,41.000,42.000,45.000,48.000,44.000,43.000,45.000,47.000,48.000,51.000,45.000,44.000,47.000,49.000,46.000,49.000,47.000,45.000,47.000,49.000,50.000,46.000,48.000,50.000,52.000,51.000,51.000,50.000,53.000,54.000,54.000,54.000,55.000,52.000,49.000,47.000,49.000,47.000,54.000,54.000,54.000,55.000,53.000,49.000,47.000,42.000,45.000,47.000,48.000,40.000,45.000,46.000,48.000,46.000,46.000,48.000,51.000,52.000,51.000,50.000,46.000,49.000,58.000,51.000,45.000,46.000,51.000,48.000,48.000,43.000,45.000,58.000,61.000,65.000,71.000,73.000,74.000,74.000,75.000,73.000,70.000,68.000,68.000,71.000,74.000,76.000,75.000,76.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,75.000,77.000,75.000,76.000,76.000,77.000,77.000,78.000,100.000,75.000,75.000,86.000,109.000,78.000,78.000,110.000,103.000,79.000,71.000,75.000,75.000,77.000,73.000,76.000,73.000,71.000,71.000,92.000,55.000,40.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,76.000,77.000,78.000,77.000,77.000,77.000,76.000,77.000,75.000,75.000,68.000,70.000,70.000,68.000,71.000,74.000,72.000,70.000,62.000,48.000,59.000,61.000,59.000,50.000,22.000,75.000,66.000,38.000,75.000,38.000,74.000,62.000}
-62.807 LMS_LASER_2D_RIGHT LMS2 ID=3988,time=1225719874.454228,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=77,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.753,19.849,15.673,12.836,10.974,9.918,9.005,8.196,7.388,6.888,6.391,5.903,5.528,5.246,4.926,4.638,4.385,4.117,3.913,3.710,3.510,3.383,3.218,3.111,2.950,2.822,2.723,2.665,2.570,2.488,2.409,2.318,2.214,2.169,2.113,2.044,1.994,1.953,1.890,1.848,1.815,1.776,1.723,1.680,1.634,1.595,1.567,1.534,1.499,1.455,1.414,1.397,1.381,1.360,1.354,1.337,1.318,1.304,1.275,1.262,1.250,1.240,1.237,1.247,1.266,1.270,1.268,1.273,1.268,1.242,1.229,1.217,1.210,1.196,1.187,1.172,1.145,1.132,1.127,1.124,1.117,1.091,1.056,1.084,1.086,1.070,1.062,1.034,0.999,0.998,1.001},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,33.000,3.000,122.000,112.000,84.000,66.000,58.000,56.000,56.000,61.000,64.000,67.000,68.000,68.000,70.000,71.000,72.000,73.000,74.000,75.000,76.000,77.000,78.000,79.000,80.000,80.000,80.000,82.000,81.000,81.000,81.000,80.000,82.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,78.000,75.000,70.000,69.000,70.000,74.000,77.000,77.000,76.000,77.000,78.000,75.000,70.000,75.000,77.000,78.000,78.000,74.000,63.000,51.000,49.000,45.000,41.000,48.000,56.000,58.000,61.000,57.000,51.000,48.000,39.000,39.000,42.000,44.000,34.000,36.000,33.000,26.000,34.000,44.000,44.000,35.000,30.000,26.000,24.000,22.000}
-62.819 LMS_LASER_2D_LEFT LMS1 ID=4116,time=1225719874.461994,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=113,Range=[181]{1.041,1.043,1.051,1.065,1.071,1.084,1.090,1.092,1.111,1.123,1.136,1.141,1.160,1.166,1.170,1.182,1.191,1.211,1.218,1.232,1.244,1.264,1.277,1.294,1.304,1.328,1.340,1.355,1.383,1.399,1.415,1.437,1.468,1.487,1.504,1.530,1.556,1.592,1.615,1.657,1.690,1.718,1.745,1.770,1.807,1.848,1.869,1.890,1.955,1.998,2.056,2.089,2.131,2.189,2.228,2.298,2.338,2.387,2.459,2.530,2.590,2.663,2.742,2.760,2.755,2.795,2.900,2.964,3.072,3.159,3.254,3.351,3.453,3.610,3.795,3.927,4.057,4.087,4.094,4.089,4.126,4.152,4.159,4.161,4.162,4.174,4.173,4.160,4.200,4.234,4.266,4.243,4.274,4.288,4.293,4.293,4.301,4.310,4.311,4.320,4.321,4.322,4.321,4.322,4.323,4.323,4.323,4.332,4.332,4.347,4.349,4.368,4.370,4.384,4.387,4.396,4.416,4.416,3.417,3.256,3.264,3.338,3.433,3.488,3.202,2.923,3.274,2.972,2.713,2.573,2.607,2.621,2.661,2.711,2.812,2.815,2.881,2.770,2.930,2.811,2.699,4.774,4.797,4.825,4.844,4.876,4.892,4.916,4.942,4.966,4.991,5.021,5.047,5.072,5.100,5.122,5.156,5.187,5.216,5.248,5.277,5.315,5.352,5.403,5.436,5.467,5.490,5.525,5.548,5.595,5.550,5.556,5.756,5.567,5.438,5.428,5.416,5.454,5.413,5.491,5.410},Reflectance=[181]{43.000,39.000,43.000,42.000,40.000,43.000,42.000,43.000,44.000,41.000,39.000,41.000,39.000,41.000,44.000,50.000,46.000,48.000,47.000,49.000,47.000,49.000,45.000,50.000,47.000,50.000,51.000,50.000,50.000,49.000,50.000,51.000,49.000,54.000,54.000,54.000,54.000,54.000,53.000,48.000,45.000,51.000,51.000,51.000,55.000,54.000,55.000,56.000,54.000,51.000,45.000,45.000,46.000,48.000,46.000,40.000,43.000,46.000,45.000,45.000,44.000,49.000,49.000,52.000,54.000,52.000,49.000,48.000,61.000,52.000,48.000,56.000,58.000,45.000,46.000,48.000,47.000,56.000,60.000,67.000,72.000,74.000,74.000,74.000,75.000,71.000,71.000,69.000,69.000,71.000,75.000,76.000,75.000,76.000,78.000,78.000,78.000,77.000,78.000,78.000,80.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,80.000,78.000,76.000,77.000,76.000,76.000,76.000,77.000,77.000,108.000,76.000,75.000,86.000,107.000,109.000,18.000,116.000,98.000,107.000,98.000,74.000,76.000,75.000,76.000,77.000,75.000,76.000,81.000,68.000,100.000,104.000,35.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,76.000,77.000,76.000,76.000,77.000,76.000,76.000,75.000,70.000,67.000,70.000,70.000,68.000,72.000,74.000,72.000,69.000,58.000,43.000,57.000,62.000,59.000,45.000,69.000,77.000,64.000,48.000,71.000,40.000,74.000,63.000}
-62.819 LMS_LASER_2D_RIGHT LMS2 ID=3989,time=1225719874.467564,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=78,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.674,18.192,15.154,12.427,10.789,9.722,8.838,8.031,7.271,6.784,6.323,5.743,5.460,5.173,4.855,4.588,4.330,4.082,3.860,3.659,3.498,3.350,3.207,3.089,2.937,2.829,2.725,2.638,2.553,2.480,2.382,2.311,2.213,2.163,2.083,2.034,1.985,1.944,1.892,1.841,1.810,1.766,1.716,1.670,1.633,1.592,1.552,1.514,1.472,1.449,1.414,1.385,1.375,1.360,1.351,1.333,1.311,1.301,1.270,1.245,1.242,1.231,1.228,1.239,1.261,1.260,1.263,1.265,1.258,1.236,1.223,1.215,1.200,1.201,1.190,1.166,1.136,1.135,1.125,1.122,1.087,1.065,1.052,1.052,1.069,1.065,1.042,1.037,1.002,0.998,0.985},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,28.000,41.000,114.000,107.000,77.000,64.000,57.000,56.000,57.000,62.000,65.000,70.000,69.000,69.000,70.000,71.000,72.000,73.000,74.000,75.000,75.000,78.000,80.000,80.000,79.000,80.000,81.000,84.000,81.000,81.000,81.000,81.000,81.000,79.000,77.000,79.000,80.000,80.000,80.000,80.000,78.000,79.000,79.000,79.000,78.000,77.000,70.000,66.000,69.000,73.000,73.000,76.000,78.000,79.000,79.000,77.000,67.000,64.000,72.000,77.000,78.000,78.000,74.000,65.000,53.000,52.000,46.000,43.000,51.000,58.000,60.000,60.000,57.000,50.000,45.000,46.000,39.000,43.000,43.000,34.000,29.000,27.000,26.000,28.000,35.000,38.000,32.000,30.000,26.000,25.000,24.000}
-62.827 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.0233,19.2941,-0.8540},Vel=[3x1]{-0.8543,-0.7444,2.6923},Raw=[2x1]{21.0956,-0.8540},time=1225719874.47436881065369,Speed=1.13314447592068,Pitch=0.02692024480606,Roll=0.02916359853990,PitchDot=0.01121676866919,RollDot=0.00109924332958
-62.827 ODOMETRY_POSE iPlatform Pose=[3x1]{5.0233,19.2941,-0.8535},Vel=[3x1]{-0.8543,-0.7444,2.6923},Raw=[2x1]{21.0956,-0.8540},time=1225719874.4744,Speed=1.1331,Pitch=-0.0043,Roll=0.0395,PitchDot=-0.0096,RollDot=-0.0059
-62.827 VEHICLE_GEOMETRY iPlatform Name=LISA, Sensor_0=LMS_LASER_2D, Pose3D_0=[4x1]{0.0000,0.3500,0.0000,0.0000},SHAPE_2D=[2x8]{0.3300,0.3300,0.2100,0.2100,-0.2100,-0.2100,-0.3300,-0.3300,-0.4100,0.4100,0.4100,0.5700,0.5700,0.4100,0.4100,-0.4100,}
-62.831 DESIRED_THRUST iJoystick 84.5393230995
-62.831 DESIRED_RUDDER iJoystick 3.09152500992
-62.839 DB_TIME MOOSDB#1 1225719874.49
-62.839 DB_UPTIME MOOSDB#1 66.3432145119
-62.855 DESIRED_THRUST iJoystick 84.5393230995
-62.855 DESIRED_RUDDER iJoystick 3.09152500992
-62.863 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.0492,19.3167,-0.8549},Vel=[3x1]{-0.8660,-0.7532,2.0513},Raw=[2x1]{21.1299,-0.8549},time=1225719874.51040863990784,Speed=1.14774685318770,Pitch=0.02692024480606,Roll=0.03140695227374,PitchDot=0.02019018360455,RollDot=0.00118897747893
-62.863 ODOMETRY_POSE iPlatform Pose=[3x1]{5.0492,19.3167,-0.8544},Vel=[3x1]{-0.8660,-0.7532,2.0512},Raw=[2x1]{21.1299,-0.8549},time=1225719874.5104,Speed=1.1477,Pitch=-0.0060,Roll=0.0409,PitchDot=-0.0083,RollDot=-0.0185
-62.830 LMS_LASER_2D_LEFT LMS1 ID=4117,time=1225719874.475333,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=114,Range=[181]{1.042,1.045,1.052,1.063,1.068,1.080,1.098,1.091,1.115,1.124,1.134,1.135,1.152,1.167,1.179,1.191,1.202,1.212,1.218,1.234,1.251,1.266,1.281,1.297,1.312,1.339,1.347,1.364,1.377,1.400,1.426,1.450,1.471,1.495,1.511,1.539,1.575,1.591,1.623,1.659,1.691,1.722,1.742,1.779,1.815,1.855,1.877,1.910,1.964,2.014,2.065,2.096,2.152,2.211,2.235,2.294,2.349,2.413,2.458,2.533,2.599,2.687,2.745,2.757,2.754,2.816,2.910,2.974,3.063,3.161,3.265,3.370,3.460,3.638,3.824,3.955,4.066,4.095,4.085,4.091,4.140,4.152,4.160,4.156,4.164,4.179,4.169,4.167,4.203,4.240,4.260,4.251,4.284,4.289,4.283,4.295,4.301,4.313,4.313,4.314,4.314,4.314,4.321,4.313,4.311,4.323,4.323,4.337,4.341,4.346,4.358,4.367,4.372,4.376,4.387,4.399,4.407,4.420,3.409,3.313,3.290,3.401,4.474,3.479,3.472,3.342,3.513,2.636,2.668,2.597,2.704,2.634,2.715,2.832,2.884,2.977,2.945,2.912,2.959,2.795,2.693,4.782,4.797,4.823,4.843,4.871,4.898,4.924,4.940,4.966,4.994,5.021,5.056,5.071,5.095,5.129,5.154,5.183,5.216,5.246,5.282,5.322,5.359,5.413,5.440,5.473,5.489,5.531,5.565,5.587,5.542,5.576,5.696,5.576,5.409,5.446,5.445,5.480,5.416,5.475,5.466},Reflectance=[181]{43.000,46.000,44.000,45.000,48.000,41.000,41.000,47.000,45.000,42.000,43.000,43.000,43.000,38.000,40.000,45.000,43.000,44.000,47.000,47.000,42.000,46.000,48.000,47.000,46.000,45.000,46.000,53.000,51.000,50.000,45.000,46.000,51.000,54.000,53.000,54.000,55.000,54.000,53.000,49.000,51.000,49.000,54.000,55.000,55.000,52.000,54.000,57.000,55.000,50.000,42.000,50.000,47.000,45.000,49.000,43.000,37.000,45.000,46.000,43.000,44.000,47.000,50.000,51.000,53.000,50.000,46.000,49.000,62.000,53.000,50.000,57.000,57.000,43.000,48.000,53.000,51.000,56.000,60.000,67.000,73.000,74.000,74.000,75.000,75.000,73.000,72.000,69.000,70.000,73.000,76.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,76.000,77.000,76.000,76.000,77.000,77.000,78.000,108.000,86.000,80.000,102.000,78.000,109.000,110.000,110.000,108.000,26.000,107.000,78.000,88.000,76.000,82.000,76.000,88.000,91.000,92.000,92.000,111.000,98.000,26.000,78.000,77.000,77.000,78.000,76.000,76.000,77.000,76.000,76.000,77.000,77.000,76.000,76.000,76.000,75.000,75.000,73.000,68.000,66.000,71.000,70.000,67.000,70.000,72.000,72.000,65.000,52.000,49.000,58.000,64.000,61.000,57.000,71.000,71.000,69.000,62.000,76.000,38.000,72.000,75.000}
-62.830 LMS_LASER_2D_RIGHT LMS2 ID=3990,time=1225719874.480898,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=79,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.913,17.601,14.509,12.126,10.558,9.599,8.734,7.854,7.172,6.696,6.208,5.614,5.423,5.119,4.782,4.518,4.274,4.044,3.839,3.627,3.465,3.327,3.186,3.053,2.910,2.805,2.697,2.597,2.518,2.462,2.361,2.284,2.201,2.141,2.078,2.019,1.967,1.927,1.875,1.828,1.801,1.750,1.707,1.651,1.615,1.581,1.532,1.514,1.466,1.454,1.423,1.402,1.370,1.351,1.351,1.324,1.303,1.276,1.253,1.241,1.240,1.230,1.227,1.246,1.248,1.255,1.262,1.245,1.235,1.227,1.212,1.209,1.197,1.185,1.183,1.155,1.133,1.125,1.119,1.105,1.072,1.066,1.049,1.042,1.073,1.072,1.060,1.022,1.003,1.000,0.991},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,2.000,66.000,120.000,99.000,75.000,61.000,56.000,57.000,59.000,63.000,66.000,71.000,67.000,68.000,70.000,72.000,72.000,74.000,75.000,76.000,76.000,79.000,79.000,80.000,81.000,80.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,78.000,80.000,80.000,79.000,80.000,80.000,79.000,78.000,79.000,79.000,78.000,79.000,74.000,60.000,66.000,74.000,75.000,72.000,76.000,77.000,79.000,79.000,76.000,68.000,66.000,74.000,78.000,78.000,77.000,73.000,62.000,59.000,54.000,49.000,58.000,57.000,61.000,63.000,61.000,59.000,54.000,46.000,35.000,38.000,43.000,41.000,32.000,28.000,28.000,26.000,26.000,35.000,40.000,35.000,29.000,27.000,24.000,23.000}
-62.842 LMS_LASER_2D_LEFT LMS1 ID=4118,time=1225719874.488670,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=115,Range=[181]{1.043,1.049,1.059,1.069,1.067,1.084,1.090,1.098,1.101,1.123,1.135,1.139,1.155,1.166,1.176,1.187,1.200,1.216,1.229,1.238,1.259,1.267,1.279,1.303,1.319,1.334,1.346,1.364,1.386,1.405,1.426,1.454,1.473,1.496,1.521,1.548,1.574,1.595,1.625,1.668,1.694,1.720,1.741,1.778,1.820,1.857,1.894,1.920,1.975,2.021,2.064,2.116,2.156,2.195,2.248,2.316,2.356,2.415,2.486,2.544,2.619,2.706,2.747,2.757,2.759,2.838,2.927,2.985,3.072,3.186,3.260,3.394,3.514,3.716,3.846,3.958,4.089,4.098,4.087,4.097,4.140,4.153,4.160,4.161,4.159,4.174,4.155,4.166,4.216,4.246,4.254,4.244,4.287,4.282,4.285,4.295,4.301,4.304,4.311,4.305,4.306,4.306,4.311,4.304,4.314,4.314,4.328,4.332,4.341,4.347,4.346,4.368,4.373,4.383,4.391,4.404,4.407,4.420,3.314,3.483,3.384,3.511,4.464,3.397,3.345,3.410,3.290,2.713,2.572,2.827,2.752,2.693,2.854,2.843,2.833,2.912,2.908,2.861,2.924,2.728,2.712,4.781,4.799,4.825,4.845,4.876,4.900,4.922,4.948,4.968,4.996,5.023,5.049,5.073,5.103,5.134,5.161,5.180,5.214,5.254,5.282,5.316,5.365,5.423,5.444,5.481,5.491,5.525,5.562,5.576,5.542,5.550,5.517,5.527,5.407,5.445,5.402,5.464,5.443,5.419,5.456},Reflectance=[181]{36.000,42.000,39.000,40.000,43.000,43.000,45.000,45.000,48.000,46.000,43.000,46.000,46.000,46.000,43.000,49.000,50.000,45.000,48.000,44.000,45.000,46.000,47.000,45.000,49.000,52.000,49.000,49.000,47.000,49.000,54.000,47.000,51.000,54.000,54.000,54.000,54.000,56.000,54.000,53.000,52.000,51.000,54.000,54.000,53.000,53.000,54.000,58.000,52.000,50.000,45.000,46.000,49.000,47.000,41.000,37.000,43.000,46.000,46.000,44.000,41.000,48.000,51.000,51.000,51.000,48.000,45.000,46.000,57.000,49.000,47.000,48.000,49.000,50.000,50.000,54.000,53.000,57.000,61.000,69.000,73.000,75.000,74.000,74.000,74.000,71.000,68.000,65.000,71.000,75.000,77.000,76.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,76.000,78.000,78.000,75.000,76.000,77.000,78.000,10.000,106.000,94.000,106.000,78.000,106.000,105.000,109.000,21.000,129.000,74.000,94.000,100.000,88.000,90.000,77.000,80.000,92.000,91.000,75.000,94.000,54.000,31.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,76.000,77.000,77.000,77.000,77.000,76.000,75.000,74.000,75.000,70.000,67.000,68.000,71.000,68.000,64.000,70.000,71.000,71.000,67.000,43.000,58.000,62.000,63.000,62.000,69.000,69.000,59.000,64.000,40.000,74.000,25.000,65.000,54.000}
-62.854 LMS_LASER_2D_LEFT LMS1 ID=4119,time=1225719874.502007,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=116,Range=[181]{1.048,1.042,1.058,1.065,1.080,1.086,1.089,1.111,1.109,1.127,1.135,1.142,1.149,1.159,1.173,1.186,1.200,1.219,1.233,1.242,1.258,1.271,1.285,1.304,1.313,1.331,1.345,1.364,1.387,1.408,1.429,1.446,1.477,1.505,1.531,1.557,1.582,1.598,1.633,1.671,1.693,1.722,1.758,1.787,1.829,1.852,1.894,1.929,1.978,2.020,2.073,2.120,2.160,2.211,2.255,2.309,2.370,2.427,2.495,2.549,2.637,2.706,2.752,2.752,2.759,2.855,2.935,2.993,3.055,3.171,3.254,3.409,3.530,3.729,3.865,3.964,4.080,4.093,4.087,4.103,4.142,4.153,4.164,4.160,4.164,4.174,4.148,4.174,4.216,4.243,4.251,4.251,4.284,4.282,4.284,4.292,4.304,4.301,4.310,4.301,4.306,4.307,4.305,4.309,4.317,4.314,4.326,4.330,4.339,4.349,4.352,4.362,4.376,4.383,4.382,4.399,4.407,4.419,4.430,4.438,4.444,4.464,3.379,3.392,3.410,3.522,4.528,2.692,2.714,3.230,2.750,2.769,2.924,2.752,2.765,2.803,2.878,2.827,2.940,2.832,2.695,4.786,4.798,4.825,4.846,4.877,4.900,4.925,4.952,4.970,4.996,5.023,5.051,5.073,5.108,5.138,5.164,5.193,5.217,5.256,5.283,5.319,5.383,5.419,5.452,5.484,5.489,5.526,5.559,5.573,5.542,5.481,5.458,5.448,5.428,5.486,5.411,5.455,5.414,5.428,5.482},Reflectance=[181]{41.000,43.000,43.000,42.000,45.000,44.000,41.000,39.000,43.000,43.000,43.000,47.000,46.000,47.000,46.000,48.000,47.000,48.000,45.000,46.000,45.000,48.000,50.000,47.000,51.000,51.000,49.000,49.000,51.000,50.000,51.000,48.000,53.000,54.000,54.000,54.000,54.000,54.000,53.000,50.000,51.000,52.000,53.000,50.000,50.000,55.000,54.000,54.000,53.000,49.000,46.000,48.000,51.000,46.000,53.000,41.000,45.000,48.000,45.000,47.000,44.000,48.000,53.000,53.000,56.000,48.000,50.000,50.000,58.000,50.000,48.000,54.000,51.000,60.000,58.000,50.000,57.000,55.000,61.000,68.000,74.000,75.000,75.000,74.000,73.000,71.000,66.000,65.000,71.000,74.000,76.000,76.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,75.000,77.000,77.000,78.000,79.000,78.000,77.000,78.000,98.000,102.000,110.000,108.000,78.000,119.000,115.000,107.000,83.000,114.000,103.000,76.000,75.000,75.000,79.000,75.000,93.000,107.000,55.000,76.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,76.000,77.000,75.000,75.000,71.000,68.000,69.000,71.000,65.000,63.000,69.000,70.000,72.000,65.000,44.000,64.000,60.000,61.000,63.000,67.000,67.000,64.000,68.000,67.000,74.000,38.000,63.000,72.000}
-62.879 DESIRED_THRUST iJoystick 84.5393230995
-62.879 DESIRED_RUDDER iJoystick 3.09152500992
-62.899 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.0835,19.3464,-0.8572},Vel=[3x1]{-0.8688,-0.7522,2.1795},Raw=[2x1]{21.1753,-0.8572},time=1225719874.54637074470520,Speed=1.14920709091440,Pitch=0.02692024480606,Roll=0.03589365974142,PitchDot=-0.00673006120152,RollDot=0.00103194271757
-62.899 ODOMETRY_POSE iPlatform Pose=[3x1]{5.0835,19.3464,-0.8565},Vel=[3x1]{-0.8688,-0.7522,2.1795},Raw=[2x1]{21.1753,-0.8572},time=1225719874.5464,Speed=1.1492,Pitch=-0.0095,Roll=0.0438,PitchDot=0.0047,RollDot=0.0049
-62.903 DESIRED_THRUST iJoystick 84.5393230995
-62.903 DESIRED_RUDDER iJoystick 3.09152500992
-62.927 DESIRED_THRUST iJoystick 84.5393230995
-62.927 DESIRED_RUDDER iJoystick 3.09152500992
-62.935 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.1182,19.3763,-0.8608},Vel=[3x1]{-0.8671,-0.7453,6.6667},Raw=[2x1]{21.2211,-0.8608},time=1225719874.58240079879761,Speed=1.14336614000759,Pitch=0.02692024480606,Roll=0.03813701347526,PitchDot=0.00224335373384,RollDot=0.00000000000000
-62.935 ODOMETRY_POSE iPlatform Pose=[3x1]{5.1182,19.3763,-0.8600},Vel=[3x1]{-0.8671,-0.7453,0.3835},Raw=[2x1]{21.2211,-0.8608},time=1225719874.5824,Speed=1.1434,Pitch=-0.0114,Roll=0.0453,PitchDot=0.0021,RollDot=-0.0008
-62.951 DESIRED_THRUST iJoystick 84.5393230995
-62.951 DESIRED_RUDDER iJoystick 3.09152500992
-62.971 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.1447,19.3990,-0.8647},Vel=[3x1]{-0.8833,-0.7533,12.5641},Raw=[2x1]{21.2560,-0.8647},time=1225719874.61836862564087,Speed=1.16088899272802,Pitch=0.02692024480606,Roll=0.03813701347526,PitchDot=0.02243353733839,RollDot=-0.00058327197080
-62.971 ODOMETRY_POSE iPlatform Pose=[3x1]{5.1447,19.3990,-0.8639},Vel=[3x1]{-0.8833,-0.7533,-0.0023},Raw=[2x1]{21.2560,-0.8647},time=1225719874.6184,Speed=1.1609,Pitch=-0.0115,Roll=0.0452,PitchDot=0.0224,RollDot=-0.0005
-62.975 DESIRED_THRUST iJoystick 84.5393230995
-62.975 DESIRED_RUDDER iJoystick 3.09152500992
-62.999 DESIRED_THRUST iJoystick 84.5393230995
-62.999 DESIRED_RUDDER iJoystick 3.09152500992
-62.842 LMS_LASER_2D_RIGHT LMS2 ID=3991,time=1225719874.494230,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=80,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,17.171,14.096,11.862,10.340,9.454,8.616,7.763,7.098,6.634,6.110,5.598,5.380,5.041,4.748,4.474,4.221,4.010,3.788,3.585,3.448,3.316,3.159,3.028,2.892,2.738,2.688,2.587,2.516,2.451,2.342,2.274,2.192,2.097,2.048,1.994,1.953,1.918,1.873,1.838,1.784,1.741,1.688,1.640,1.607,1.578,1.522,1.501,1.491,1.461,1.429,1.399,1.355,1.354,1.345,1.321,1.297,1.286,1.253,1.239,1.233,1.237,1.233,1.239,1.250,1.262,1.272,1.260,1.229,1.213,1.205,1.205,1.207,1.184,1.180,1.154,1.129,1.127,1.124,1.118,1.104,1.064,1.080,1.070,1.070,1.065,1.053,0.997,0.998,0.993,0.995},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,80.000,117.000,94.000,74.000,60.000,56.000,57.000,58.000,63.000,68.000,71.000,68.000,69.000,71.000,72.000,72.000,74.000,76.000,77.000,77.000,78.000,79.000,80.000,81.000,82.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,70.000,66.000,74.000,76.000,75.000,76.000,75.000,75.000,77.000,77.000,76.000,73.000,68.000,73.000,77.000,78.000,77.000,68.000,59.000,56.000,46.000,46.000,49.000,58.000,65.000,65.000,64.000,52.000,53.000,48.000,42.000,40.000,44.000,42.000,41.000,39.000,27.000,34.000,37.000,40.000,41.000,35.000,26.000,25.000,24.000,23.000}
-62.866 LMS_LASER_2D_LEFT LMS1 ID=4120,time=1225719874.515342,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=117,Range=[181]{1.040,1.048,1.054,1.068,1.077,1.083,1.088,1.103,1.111,1.132,1.135,1.147,1.160,1.163,1.182,1.187,1.206,1.220,1.234,1.243,1.253,1.273,1.292,1.303,1.315,1.336,1.350,1.365,1.389,1.408,1.439,1.448,1.482,1.495,1.531,1.564,1.581,1.612,1.655,1.672,1.699,1.724,1.756,1.796,1.832,1.861,1.904,1.937,1.982,2.029,2.066,2.125,2.163,2.220,2.268,2.324,2.371,2.425,2.501,2.566,2.643,2.714,2.746,2.747,2.750,2.876,2.941,3.000,3.028,3.133,3.278,3.421,3.538,3.761,3.888,3.973,4.053,4.087,4.086,4.110,4.142,4.155,4.155,4.160,4.160,4.167,4.149,4.174,4.219,4.252,4.244,4.252,4.273,4.283,4.285,4.293,4.291,4.299,4.301,4.304,4.309,4.306,4.298,4.306,4.305,4.314,4.317,4.330,4.337,4.348,4.355,4.364,4.374,4.382,4.385,4.399,4.410,4.421,4.430,4.439,4.447,3.418,3.242,3.365,3.387,3.292,4.524,2.573,4.554,3.225,3.280,3.130,2.790,2.759,2.774,2.906,2.914,2.882,2.890,2.714,2.698,2.810,2.814,4.825,4.845,4.868,4.891,4.916,4.951,4.971,4.998,5.024,5.051,5.073,5.107,5.131,5.163,5.191,5.222,5.259,5.284,5.328,5.383,5.419,5.448,5.472,5.502,5.517,5.570,5.580,5.540,5.481,5.445,5.445,5.430,5.437,5.383,5.459,5.478,5.439,5.437},Reflectance=[181]{38.000,42.000,46.000,39.000,44.000,42.000,46.000,44.000,44.000,45.000,43.000,46.000,43.000,49.000,45.000,44.000,41.000,43.000,42.000,47.000,43.000,44.000,44.000,45.000,51.000,53.000,51.000,54.000,52.000,53.000,48.000,52.000,52.000,54.000,54.000,53.000,53.000,48.000,42.000,47.000,50.000,54.000,52.000,50.000,51.000,51.000,55.000,54.000,55.000,53.000,55.000,54.000,52.000,45.000,47.000,40.000,50.000,47.000,45.000,45.000,43.000,48.000,54.000,54.000,55.000,45.000,52.000,49.000,57.000,57.000,51.000,51.000,54.000,58.000,54.000,50.000,66.000,56.000,60.000,70.000,74.000,75.000,75.000,74.000,72.000,69.000,65.000,66.000,72.000,74.000,76.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,76.000,77.000,78.000,78.000,79.000,79.000,78.000,93.000,72.000,93.000,105.000,23.000,77.000,25.000,78.000,103.000,110.000,118.000,81.000,75.000,75.000,79.000,84.000,91.000,95.000,56.000,56.000,47.000,56.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,76.000,76.000,76.000,75.000,71.000,67.000,70.000,69.000,65.000,61.000,64.000,67.000,66.000,59.000,42.000,58.000,59.000,60.000,61.000,62.000,64.000,67.000,69.000,65.000,75.000,78.000,67.000,65.000}
-62.866 LMS_LASER_2D_RIGHT LMS2 ID=3992,time=1225719874.507573,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=81,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.229,-1.000,16.652,13.799,11.605,10.204,9.319,8.484,7.667,7.016,6.563,6.053,5.663,5.327,4.998,4.715,4.429,4.185,3.982,3.763,3.563,3.432,3.296,3.147,3.020,2.875,2.772,2.673,2.570,2.517,2.426,2.335,2.265,2.184,2.091,2.063,2.002,1.953,1.908,1.872,1.829,1.774,1.739,1.698,1.634,1.571,1.562,1.536,1.519,1.494,1.445,1.426,1.379,1.362,1.357,1.339,1.317,1.303,1.279,1.257,1.243,1.233,1.229,1.238,1.243,1.242,1.263,1.267,1.255,1.223,1.220,1.205,1.203,1.212,1.191,1.167,1.161,1.132,1.118,1.115,1.072,1.067,1.084,1.090,1.076,1.069,1.058,1.019,1.005,0.993,0.998,0.988},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,0.000,94.000,110.000,91.000,71.000,60.000,56.000,57.000,57.000,64.000,67.000,67.000,68.000,70.000,70.000,72.000,73.000,74.000,76.000,75.000,77.000,77.000,76.000,81.000,81.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,79.000,79.000,79.000,78.000,79.000,79.000,77.000,73.000,72.000,73.000,77.000,77.000,75.000,75.000,76.000,77.000,78.000,78.000,77.000,75.000,72.000,75.000,78.000,78.000,74.000,64.000,61.000,56.000,46.000,41.000,50.000,60.000,62.000,66.000,58.000,41.000,45.000,53.000,43.000,42.000,43.000,40.000,28.000,26.000,32.000,38.000,41.000,42.000,36.000,28.000,27.000,26.000,25.000,23.000}
-62.878 LMS_LASER_2D_LEFT LMS1 ID=4121,time=1225719874.528675,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=118,Range=[181]{1.037,1.050,1.058,1.069,1.078,1.086,1.087,1.107,1.120,1.124,1.131,1.145,1.155,1.167,1.176,1.199,1.209,1.227,1.223,1.245,1.264,1.275,1.286,1.304,1.323,1.331,1.356,1.369,1.391,1.408,1.432,1.459,1.482,1.503,1.531,1.556,1.583,1.616,1.651,1.679,1.704,1.724,1.766,1.801,1.833,1.870,1.894,1.947,1.990,2.041,2.077,2.123,2.151,2.216,2.264,2.327,2.375,2.436,2.505,2.574,2.640,2.722,2.750,2.732,2.755,2.886,2.954,3.012,3.076,3.179,3.303,3.425,3.555,3.804,3.913,3.991,4.061,4.090,4.088,4.107,4.143,4.153,4.152,4.156,4.153,4.161,4.157,4.174,4.217,4.245,4.246,4.253,4.280,4.282,4.275,4.281,4.291,4.301,4.299,4.304,4.309,4.294,4.306,4.305,4.304,4.307,4.315,4.323,4.331,4.346,4.356,4.357,4.375,4.373,4.385,4.399,4.402,4.421,4.421,4.435,3.373,3.183,3.213,3.246,3.366,4.509,4.525,4.536,3.185,4.566,4.583,2.857,2.875,2.774,2.816,2.860,2.799,2.930,2.947,2.755,2.840,2.803,2.821,4.827,4.846,4.868,4.893,4.924,4.942,4.969,4.997,5.022,5.049,5.073,5.097,5.131,5.164,5.189,5.223,5.265,5.286,5.319,5.365,5.406,5.448,5.477,5.513,5.508,5.577,5.565,5.536,5.559,5.430,5.445,5.454,5.392,5.392,5.404,5.474,5.437,5.453},Reflectance=[181]{40.000,38.000,43.000,44.000,44.000,44.000,44.000,45.000,44.000,42.000,49.000,44.000,46.000,47.000,47.000,45.000,42.000,43.000,46.000,43.000,44.000,46.000,45.000,47.000,47.000,47.000,50.000,48.000,53.000,53.000,53.000,50.000,52.000,53.000,54.000,54.000,54.000,50.000,46.000,50.000,52.000,54.000,49.000,49.000,51.000,55.000,54.000,55.000,54.000,51.000,48.000,53.000,54.000,48.000,40.000,41.000,44.000,48.000,42.000,41.000,46.000,55.000,56.000,55.000,57.000,47.000,47.000,50.000,48.000,46.000,46.000,53.000,54.000,50.000,57.000,50.000,64.000,58.000,61.000,69.000,74.000,75.000,74.000,73.000,72.000,67.000,64.000,66.000,71.000,74.000,77.000,76.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,78.000,79.000,78.000,80.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,77.000,78.000,78.000,78.000,77.000,108.000,75.000,79.000,80.000,102.000,78.000,77.000,78.000,6.000,78.000,78.000,32.000,113.000,75.000,74.000,76.000,74.000,108.000,115.000,36.000,98.000,75.000,56.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,76.000,76.000,76.000,75.000,70.000,70.000,69.000,67.000,64.000,61.000,59.000,58.000,59.000,59.000,40.000,57.000,60.000,58.000,61.000,69.000,64.000,64.000,64.000,61.000,45.000,75.000,69.000,66.000}
-62.878 LMS_LASER_2D_RIGHT LMS2 ID=3993,time=1225719874.520914,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=82,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.143,-1.000,16.387,13.264,11.382,10.115,9.213,8.376,7.592,6.977,6.513,6.008,5.629,5.283,4.963,4.681,4.384,4.169,3.951,3.746,3.549,3.413,3.280,3.097,2.985,2.855,2.762,2.645,2.553,2.487,2.400,2.319,2.246,2.175,2.131,2.070,2.010,1.954,1.892,1.859,1.821,1.767,1.732,1.680,1.611,1.560,1.545,1.527,1.507,1.470,1.437,1.418,1.388,1.366,1.360,1.340,1.316,1.295,1.266,1.256,1.241,1.233,1.221,1.233,1.238,1.249,1.259,1.262,1.234,1.214,1.203,1.205,1.191,1.201,1.188,1.169,1.136,1.127,1.116,1.107,1.071,1.062,1.055,1.078,1.067,1.069,1.057,1.019,1.025,0.989,0.987,0.982},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,17.000,0.000,103.000,120.000,90.000,68.000,59.000,56.000,56.000,61.000,65.000,68.000,66.000,67.000,70.000,72.000,72.000,73.000,75.000,75.000,77.000,77.000,78.000,80.000,81.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,77.000,78.000,79.000,79.000,79.000,79.000,75.000,69.000,73.000,73.000,75.000,75.000,76.000,78.000,76.000,78.000,79.000,78.000,77.000,76.000,75.000,77.000,78.000,78.000,75.000,68.000,63.000,55.000,45.000,40.000,53.000,59.000,62.000,65.000,61.000,46.000,48.000,51.000,32.000,39.000,42.000,36.000,27.000,27.000,27.000,37.000,34.000,37.000,36.000,29.000,30.000,26.000,25.000,24.000}
-62.890 LMS_LASER_2D_RIGHT LMS2 ID=3994,time=1225719874.534254,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=83,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.070,-1.000,16.119,13.105,11.255,10.028,9.095,8.305,7.508,6.887,6.458,5.964,5.604,5.255,4.927,4.647,4.366,4.134,3.941,3.724,3.548,3.390,3.251,3.054,2.985,2.848,2.750,2.629,2.545,2.472,2.397,2.309,2.246,2.175,2.122,2.065,2.002,1.933,1.860,1.842,1.812,1.760,1.715,1.661,1.598,1.561,1.549,1.538,1.507,1.466,1.440,1.420,1.390,1.366,1.357,1.336,1.308,1.280,1.259,1.242,1.236,1.228,1.226,1.233,1.242,1.252,1.264,1.263,1.246,1.211,1.196,1.180,1.172,1.186,1.184,1.159,1.155,1.115,1.118,1.108,1.074,1.058,1.080,1.082,1.075,1.058,1.053,1.043,1.029,0.996,0.986,0.981},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,20.000,0.000,111.000,118.000,84.000,66.000,59.000,55.000,55.000,61.000,65.000,68.000,66.000,68.000,71.000,72.000,72.000,73.000,75.000,76.000,76.000,76.000,78.000,80.000,81.000,78.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,78.000,80.000,77.000,76.000,78.000,79.000,79.000,79.000,79.000,74.000,71.000,75.000,77.000,75.000,74.000,76.000,78.000,77.000,78.000,78.000,77.000,74.000,73.000,76.000,78.000,79.000,79.000,76.000,68.000,60.000,52.000,41.000,40.000,46.000,58.000,64.000,67.000,67.000,54.000,53.000,54.000,35.000,38.000,43.000,36.000,27.000,28.000,34.000,38.000,41.000,41.000,40.000,35.000,32.000,25.000,24.000,25.000}
-62.902 LMS_LASER_2D_LEFT LMS1 ID=4122,time=1225719874.542019,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=119,Range=[181]{1.039,1.048,1.057,1.064,1.075,1.082,1.090,1.101,1.122,1.124,1.135,1.149,1.156,1.169,1.174,1.197,1.208,1.214,1.227,1.245,1.263,1.276,1.289,1.300,1.319,1.340,1.351,1.371,1.392,1.415,1.433,1.462,1.481,1.504,1.530,1.556,1.590,1.616,1.653,1.676,1.706,1.723,1.764,1.805,1.839,1.865,1.895,1.938,1.990,2.023,2.083,2.127,2.169,2.215,2.271,2.339,2.381,2.438,2.513,2.572,2.657,2.703,2.749,2.739,2.751,2.863,2.964,3.033,3.085,3.179,3.292,3.417,3.583,3.798,3.926,4.023,4.058,4.091,4.088,4.104,4.143,4.153,4.158,4.152,4.157,4.167,4.149,4.174,4.219,4.245,4.235,4.244,4.271,4.273,4.275,4.282,4.291,4.300,4.299,4.301,4.304,4.295,4.295,4.295,4.306,4.307,4.314,4.323,4.332,4.340,4.348,4.357,4.367,4.374,4.381,4.397,4.403,4.412,4.422,4.438,3.290,3.218,3.183,3.227,3.329,3.229,4.528,4.536,4.545,4.565,4.588,2.841,2.881,2.800,2.654,2.589,2.782,2.849,2.780,2.645,2.725,2.834,2.825,4.827,4.846,4.868,4.890,4.915,4.942,4.970,4.988,5.015,5.051,5.073,5.098,5.133,5.163,5.190,5.237,5.259,5.286,5.317,5.347,5.392,5.437,5.463,5.503,5.510,5.580,5.573,5.539,5.594,5.429,5.437,5.426,5.437,5.391,5.427,5.481,5.396,5.485},Reflectance=[181]{41.000,42.000,42.000,45.000,43.000,42.000,42.000,43.000,40.000,45.000,48.000,42.000,45.000,43.000,46.000,40.000,45.000,49.000,47.000,43.000,43.000,46.000,48.000,49.000,49.000,47.000,48.000,52.000,54.000,50.000,49.000,51.000,51.000,54.000,54.000,54.000,53.000,50.000,46.000,52.000,53.000,54.000,52.000,54.000,54.000,56.000,55.000,55.000,54.000,54.000,51.000,55.000,55.000,48.000,40.000,39.000,45.000,44.000,42.000,44.000,54.000,58.000,55.000,55.000,60.000,51.000,48.000,48.000,48.000,50.000,50.000,58.000,45.000,48.000,48.000,48.000,68.000,54.000,61.000,68.000,74.000,75.000,73.000,72.000,71.000,69.000,65.000,66.000,72.000,74.000,76.000,76.000,76.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,79.000,79.000,78.000,105.000,83.000,75.000,81.000,99.000,27.000,78.000,78.000,78.000,78.000,79.000,30.000,95.000,77.000,81.000,79.000,87.000,53.000,46.000,35.000,92.000,101.000,20.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,76.000,76.000,76.000,75.000,70.000,74.000,70.000,70.000,68.000,66.000,63.000,61.000,63.000,59.000,42.000,59.000,59.000,60.000,61.000,67.000,65.000,34.000,62.000,66.000,74.000,74.000,70.000,81.000}
-62.902 LMS_LASER_2D_RIGHT LMS2 ID=3995,time=1225719874.547593,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=84,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.239,-1.000,15.844,12.995,11.205,9.987,9.034,8.252,7.455,6.851,6.425,5.928,5.569,5.219,4.899,4.614,4.348,4.108,3.923,3.732,3.515,3.362,3.235,3.036,2.969,2.820,2.741,2.616,2.535,2.463,2.380,2.307,2.233,2.157,2.123,2.057,2.000,1.932,1.882,1.841,1.804,1.748,1.695,1.638,1.604,1.567,1.545,1.529,1.491,1.466,1.432,1.400,1.382,1.363,1.333,1.315,1.292,1.276,1.250,1.251,1.236,1.228,1.224,1.218,1.235,1.256,1.255,1.256,1.248,1.221,1.190,1.174,1.174,1.184,1.163,1.156,1.157,1.123,1.112,1.107,1.072,1.058,1.087,1.078,1.075,1.061,1.050,1.037,1.022,1.002,0.985,0.983},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,0.000,115.000,117.000,82.000,66.000,59.000,54.000,55.000,61.000,66.000,67.000,67.000,68.000,70.000,72.000,72.000,74.000,75.000,76.000,78.000,76.000,78.000,80.000,81.000,75.000,80.000,81.000,81.000,81.000,80.000,79.000,79.000,80.000,81.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,78.000,78.000,76.000,75.000,74.000,77.000,76.000,73.000,76.000,78.000,78.000,77.000,74.000,74.000,75.000,75.000,76.000,78.000,79.000,79.000,78.000,73.000,61.000,50.000,41.000,41.000,47.000,58.000,68.000,75.000,69.000,61.000,59.000,56.000,46.000,40.000,42.000,38.000,29.000,28.000,37.000,44.000,41.000,42.000,34.000,34.000,31.000,29.000,24.000,24.000}
-62.914 LMS_LASER_2D_LEFT LMS1 ID=4123,time=1225719874.555362,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=120,Range=[181]{1.042,1.045,1.065,1.067,1.073,1.090,1.092,1.106,1.116,1.117,1.141,1.145,1.155,1.165,1.182,1.202,1.207,1.224,1.221,1.246,1.257,1.277,1.294,1.296,1.321,1.337,1.349,1.371,1.395,1.417,1.440,1.469,1.486,1.513,1.529,1.566,1.582,1.620,1.650,1.674,1.700,1.724,1.762,1.788,1.822,1.858,1.901,1.948,1.990,2.026,2.077,2.126,2.171,2.212,2.273,2.317,2.382,2.440,2.510,2.584,2.666,2.702,2.746,2.731,2.754,2.825,2.971,3.048,3.098,3.172,3.303,3.436,3.559,3.800,3.921,4.027,4.078,4.089,4.079,4.103,4.134,4.156,4.146,4.142,4.158,4.154,4.141,4.167,4.209,4.245,4.237,4.250,4.271,4.275,4.276,4.281,4.299,4.300,4.301,4.301,4.306,4.287,4.291,4.295,4.311,4.307,4.314,4.328,4.332,4.342,4.348,4.357,4.358,4.375,4.383,4.394,4.401,4.413,4.421,4.438,3.215,3.247,3.222,3.243,3.337,3.239,4.520,4.536,4.545,4.563,2.835,3.048,2.893,2.810,2.652,2.534,2.650,2.928,2.754,2.720,2.636,2.761,2.871,4.816,4.835,4.869,4.891,4.916,4.934,4.961,4.990,5.016,5.040,5.065,5.089,5.125,5.154,5.199,5.239,5.256,5.287,5.324,5.353,5.383,5.416,5.457,5.489,5.516,5.565,5.562,5.537,5.533,5.437,5.413,5.406,5.463,5.434,5.398,5.520,5.426,5.452},Reflectance=[181]{43.000,46.000,42.000,39.000,45.000,42.000,43.000,45.000,41.000,47.000,42.000,49.000,46.000,45.000,41.000,38.000,41.000,46.000,49.000,48.000,49.000,45.000,46.000,51.000,45.000,46.000,51.000,52.000,48.000,45.000,44.000,45.000,50.000,54.000,53.000,54.000,54.000,48.000,44.000,51.000,55.000,54.000,51.000,55.000,54.000,58.000,58.000,55.000,54.000,56.000,52.000,54.000,51.000,46.000,41.000,32.000,43.000,46.000,46.000,45.000,54.000,58.000,54.000,55.000,63.000,58.000,47.000,47.000,46.000,50.000,45.000,50.000,51.000,43.000,46.000,54.000,56.000,53.000,63.000,70.000,74.000,75.000,72.000,71.000,71.000,68.000,64.000,67.000,71.000,74.000,77.000,76.000,76.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,24.000,84.000,76.000,77.000,98.000,14.000,78.000,78.000,78.000,77.000,17.000,120.000,98.000,77.000,82.000,76.000,98.000,92.000,50.000,96.000,62.000,49.000,17.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,76.000,77.000,75.000,73.000,74.000,71.000,72.000,73.000,71.000,69.000,68.000,67.000,62.000,53.000,59.000,58.000,59.000,63.000,63.000,58.000,35.000,61.000,76.000,21.000,75.000,76.000,68.000}
-62.915 LMS_LASER_2D_RIGHT LMS2 ID=3996,time=1225719874.560931,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=85,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.906,-1.000,15.672,12.846,11.074,9.875,8.998,8.201,7.395,6.823,6.408,5.912,5.544,5.210,4.873,4.604,4.340,4.091,3.906,3.714,3.528,3.350,3.242,3.038,2.941,2.808,2.725,2.607,2.527,2.451,2.380,2.298,2.206,2.151,2.106,2.055,1.993,1.944,1.892,1.841,1.795,1.736,1.697,1.636,1.618,1.590,1.537,1.507,1.478,1.457,1.436,1.409,1.390,1.360,1.332,1.306,1.295,1.277,1.262,1.245,1.228,1.225,1.222,1.216,1.240,1.248,1.254,1.256,1.253,1.222,1.191,1.171,1.180,1.174,1.158,1.148,1.140,1.111,1.116,1.107,1.066,1.052,1.090,1.081,1.069,1.056,1.049,1.045,1.018,0.993,0.988,0.978},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,23.000,0.000,121.000,112.000,81.000,66.000,58.000,54.000,55.000,60.000,65.000,68.000,67.000,68.000,71.000,71.000,73.000,74.000,75.000,76.000,77.000,78.000,80.000,81.000,80.000,76.000,81.000,81.000,81.000,80.000,80.000,79.000,79.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,79.000,78.000,79.000,77.000,77.000,77.000,74.000,76.000,75.000,73.000,75.000,78.000,77.000,74.000,71.000,73.000,76.000,76.000,77.000,77.000,77.000,78.000,77.000,71.000,59.000,47.000,42.000,38.000,46.000,59.000,69.000,75.000,66.000,61.000,57.000,60.000,52.000,37.000,42.000,34.000,25.000,26.000,38.000,49.000,42.000,40.000,36.000,37.000,31.000,26.000,23.000,23.000}
-62.926 LMS_LASER_2D_LEFT LMS1 ID=4124,time=1225719874.568704,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=121,Range=[181]{1.048,1.043,1.056,1.064,1.073,1.088,1.097,1.101,1.110,1.122,1.134,1.145,1.147,1.167,1.181,1.204,1.207,1.223,1.237,1.243,1.259,1.276,1.293,1.300,1.320,1.336,1.353,1.380,1.395,1.426,1.445,1.471,1.493,1.504,1.539,1.565,1.591,1.618,1.656,1.682,1.706,1.732,1.769,1.796,1.827,1.861,1.901,1.937,1.994,2.032,2.075,2.128,2.166,2.214,2.278,2.334,2.379,2.436,2.511,2.577,2.649,2.686,2.747,2.732,2.761,2.859,2.958,3.054,3.117,3.186,3.292,3.446,3.627,3.792,3.921,3.982,4.081,4.085,4.070,4.108,4.134,4.143,4.145,4.143,4.150,4.158,4.133,4.171,4.210,4.248,4.236,4.249,4.264,4.265,4.277,4.286,4.290,4.299,4.299,4.293,4.295,4.298,4.289,4.295,4.306,4.305,4.309,4.315,4.322,4.333,4.341,4.349,4.359,4.365,4.376,4.391,4.401,4.412,4.424,4.429,4.444,3.520,3.579,3.333,3.294,4.507,4.519,4.528,4.546,4.564,4.574,3.018,2.971,2.849,2.812,2.587,2.551,2.704,2.859,2.766,2.691,2.808,2.853,4.820,4.837,4.861,4.885,4.908,4.933,4.961,4.980,5.015,5.042,5.066,5.090,5.127,5.158,5.192,5.231,5.260,5.286,5.327,5.353,5.384,5.417,5.449,5.498,5.510,5.559,5.556,5.533,5.609,5.439,5.428,5.367,5.445,5.491,5.403,5.662,5.457,5.437},Reflectance=[181]{38.000,44.000,45.000,46.000,42.000,41.000,41.000,43.000,48.000,46.000,43.000,49.000,50.000,47.000,41.000,40.000,37.000,41.000,43.000,47.000,45.000,45.000,46.000,49.000,50.000,53.000,49.000,49.000,48.000,45.000,47.000,42.000,49.000,54.000,54.000,54.000,54.000,47.000,42.000,47.000,53.000,54.000,54.000,54.000,52.000,55.000,57.000,54.000,52.000,55.000,55.000,51.000,53.000,42.000,43.000,37.000,53.000,48.000,46.000,43.000,59.000,59.000,54.000,55.000,60.000,57.000,49.000,45.000,46.000,49.000,46.000,45.000,46.000,43.000,49.000,58.000,58.000,55.000,65.000,72.000,74.000,74.000,72.000,72.000,71.000,69.000,65.000,68.000,72.000,75.000,76.000,75.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,77.000,107.000,102.000,80.000,100.000,77.000,78.000,78.000,78.000,78.000,78.000,116.000,113.000,85.000,78.000,80.000,76.000,98.000,115.000,96.000,64.000,72.000,34.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,76.000,75.000,72.000,72.000,74.000,71.000,69.000,68.000,67.000,62.000,58.000,61.000,60.000,61.000,59.000,54.000,65.000,40.000,64.000,74.000,35.000,71.000,75.000,65.000}
-62.926 LMS_LASER_2D_RIGHT LMS2 ID=3997,time=1225719874.574268,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=86,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.532,-1.000,15.680,12.846,11.066,9.858,8.982,8.201,7.386,6.833,6.408,5.911,5.544,5.201,4.864,4.604,4.331,4.091,3.905,3.706,3.486,3.338,3.231,3.030,2.926,2.812,2.723,2.589,2.527,2.454,2.383,2.287,2.207,2.149,2.096,2.045,1.977,1.927,1.885,1.841,1.791,1.745,1.707,1.671,1.638,1.582,1.540,1.506,1.475,1.449,1.434,1.418,1.385,1.357,1.323,1.325,1.292,1.271,1.255,1.248,1.238,1.219,1.211,1.232,1.237,1.251,1.255,1.254,1.251,1.217,1.197,1.182,1.187,1.180,1.158,1.145,1.135,1.118,1.111,1.104,1.061,1.073,1.086,1.063,1.076,1.059,1.051,1.036,0.999,0.990,0.983,0.987},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,40.000,0.000,120.000,112.000,81.000,66.000,59.000,54.000,55.000,61.000,64.000,67.000,68.000,69.000,71.000,71.000,72.000,74.000,75.000,76.000,77.000,77.000,79.000,81.000,81.000,77.000,80.000,81.000,81.000,81.000,81.000,79.000,79.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,78.000,79.000,79.000,78.000,77.000,75.000,75.000,76.000,76.000,75.000,78.000,76.000,68.000,72.000,77.000,75.000,72.000,74.000,77.000,77.000,77.000,74.000,66.000,58.000,45.000,41.000,38.000,40.000,53.000,66.000,70.000,64.000,56.000,53.000,59.000,54.000,39.000,44.000,37.000,26.000,29.000,44.000,56.000,43.000,41.000,39.000,33.000,28.000,26.000,24.000,23.000}
-62.938 LMS_LASER_2D_LEFT LMS1 ID=4125,time=1225719874.582044,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=122,Range=[181]{1.035,1.048,1.056,1.067,1.080,1.081,1.096,1.101,1.111,1.127,1.130,1.138,1.149,1.159,1.174,1.191,1.207,1.222,1.235,1.242,1.262,1.277,1.292,1.301,1.319,1.334,1.354,1.373,1.396,1.429,1.440,1.463,1.478,1.508,1.531,1.567,1.596,1.618,1.653,1.679,1.703,1.727,1.760,1.803,1.829,1.869,1.896,1.933,1.995,2.016,2.057,2.107,2.167,2.212,2.267,2.319,2.359,2.389,2.501,2.544,2.636,2.690,2.741,2.738,2.766,2.877,2.962,3.050,3.124,3.188,3.306,3.457,3.643,3.795,3.894,4.011,4.071,4.075,4.061,4.102,4.125,4.135,4.149,4.135,4.146,4.154,4.138,4.162,4.210,4.236,4.237,4.241,4.262,4.267,4.271,4.280,4.290,4.289,4.288,4.295,4.286,4.287,4.289,4.287,4.296,4.306,4.309,4.314,4.326,4.332,4.341,4.349,4.358,4.368,4.373,4.382,4.390,4.402,4.411,4.427,4.434,4.453,3.555,3.293,3.296,4.497,4.519,4.520,2.997,2.948,2.918,2.740,2.641,2.595,2.642,2.730,2.585,2.584,2.843,2.802,2.707,2.916,2.854,4.808,4.834,4.862,4.885,4.906,4.938,4.961,4.979,5.014,5.033,5.066,5.088,5.133,5.151,5.191,5.234,5.257,5.279,5.317,5.344,5.378,5.409,5.445,5.495,5.518,5.550,5.550,5.524,5.603,5.507,5.476,6.697,5.429,5.443,5.384,5.649,5.481,5.454},Reflectance=[181]{40.000,41.000,46.000,43.000,45.000,45.000,40.000,43.000,39.000,43.000,46.000,46.000,46.000,47.000,46.000,45.000,41.000,37.000,38.000,46.000,48.000,45.000,44.000,49.000,50.000,48.000,49.000,50.000,44.000,38.000,49.000,47.000,54.000,52.000,54.000,51.000,53.000,47.000,46.000,53.000,52.000,51.000,50.000,53.000,50.000,55.000,55.000,56.000,53.000,55.000,58.000,54.000,54.000,45.000,42.000,42.000,57.000,58.000,46.000,49.000,61.000,56.000,51.000,54.000,55.000,47.000,47.000,48.000,49.000,46.000,48.000,43.000,46.000,43.000,52.000,55.000,58.000,59.000,65.000,73.000,74.000,75.000,73.000,69.000,70.000,70.000,68.000,68.000,72.000,74.000,77.000,75.000,76.000,78.000,76.000,77.000,77.000,77.000,76.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,105.000,79.000,102.000,77.000,78.000,78.000,30.000,33.000,42.000,114.000,99.000,82.000,84.000,79.000,80.000,77.000,101.000,95.000,71.000,96.000,38.000,78.000,78.000,78.000,78.000,76.000,76.000,77.000,78.000,77.000,78.000,77.000,76.000,76.000,77.000,76.000,75.000,72.000,73.000,73.000,71.000,68.000,66.000,64.000,60.000,58.000,63.000,65.000,63.000,61.000,57.000,70.000,25.000,35.000,68.000,40.000,69.000,62.000,69.000}
-62.938 LMS_LASER_2D_RIGHT LMS2 ID=3998,time=1225719874.587602,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=87,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.390,19.895,15.733,12.872,11.103,9.875,9.017,8.235,7.445,6.865,6.417,5.920,5.552,5.201,4.881,4.596,4.331,4.083,3.912,3.712,3.511,3.350,3.239,3.032,2.936,2.813,2.703,2.599,2.527,2.454,2.374,2.300,2.218,2.149,2.097,2.038,1.966,1.927,1.885,1.824,1.762,1.749,1.707,1.661,1.631,1.576,1.532,1.496,1.466,1.440,1.422,1.403,1.374,1.351,1.327,1.328,1.305,1.279,1.256,1.248,1.226,1.224,1.221,1.223,1.234,1.252,1.255,1.250,1.251,1.240,1.213,1.190,1.187,1.172,1.144,1.144,1.134,1.118,1.118,1.100,1.102,1.093,1.072,1.060,1.069,1.065,1.049,1.044,0.984,0.991,0.990,0.975},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,6.000,118.000,114.000,81.000,66.000,59.000,54.000,54.000,60.000,65.000,67.000,67.000,68.000,70.000,71.000,73.000,74.000,74.000,76.000,77.000,78.000,79.000,81.000,81.000,78.000,79.000,81.000,81.000,81.000,81.000,80.000,80.000,81.000,81.000,81.000,79.000,80.000,80.000,80.000,78.000,79.000,79.000,79.000,78.000,75.000,75.000,75.000,79.000,79.000,72.000,70.000,75.000,73.000,75.000,78.000,72.000,71.000,75.000,77.000,78.000,78.000,77.000,67.000,61.000,48.000,41.000,39.000,39.000,41.000,59.000,67.000,63.000,56.000,58.000,62.000,54.000,41.000,43.000,38.000,39.000,51.000,60.000,64.000,51.000,42.000,38.000,35.000,27.000,24.000,22.000,24.000}
-62.951 LMS_LASER_2D_LEFT LMS1 ID=4126,time=1225719874.595384,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=123,Range=[181]{1.043,1.048,1.053,1.069,1.067,1.076,1.092,1.094,1.109,1.123,1.126,1.145,1.152,1.163,1.178,1.189,1.199,1.221,1.233,1.245,1.251,1.268,1.286,1.303,1.316,1.337,1.358,1.376,1.393,1.426,1.433,1.458,1.479,1.513,1.534,1.562,1.592,1.611,1.653,1.665,1.683,1.731,1.759,1.791,1.830,1.865,1.895,1.933,1.977,2.024,2.055,2.099,2.152,2.212,2.263,2.326,2.357,2.414,2.494,2.571,2.643,2.706,2.733,2.730,2.768,2.885,2.969,3.037,3.116,3.204,3.293,3.455,3.643,3.783,3.888,4.000,4.070,4.071,4.061,4.091,4.128,4.137,4.138,4.130,4.141,4.153,4.128,4.153,4.203,4.237,4.227,4.242,4.262,4.259,4.271,4.281,4.290,4.279,4.281,4.273,4.279,4.283,4.278,4.289,4.286,4.295,4.294,4.305,4.314,4.328,4.339,4.339,4.348,4.356,4.376,4.383,4.394,4.401,4.411,4.418,4.437,4.445,3.451,3.324,4.484,4.501,4.504,3.020,2.969,2.876,2.914,2.676,2.561,2.549,2.560,2.595,2.610,2.531,2.536,2.653,2.714,2.830,4.781,4.799,4.826,4.854,4.874,4.910,4.931,4.952,4.971,5.006,5.033,5.057,5.089,5.125,5.150,5.191,5.228,5.250,5.276,5.310,5.336,5.364,5.402,5.445,5.483,5.496,5.533,5.550,5.524,5.593,5.609,5.530,6.695,6.727,5.463,5.451,5.642,5.524,5.523},Reflectance=[181]{39.000,42.000,40.000,44.000,43.000,43.000,38.000,44.000,43.000,41.000,43.000,44.000,43.000,44.000,44.000,46.000,45.000,44.000,45.000,43.000,46.000,46.000,46.000,46.000,48.000,49.000,42.000,47.000,47.000,45.000,46.000,49.000,54.000,54.000,52.000,52.000,54.000,48.000,45.000,55.000,55.000,49.000,54.000,52.000,54.000,53.000,55.000,56.000,53.000,55.000,57.000,54.000,55.000,46.000,44.000,46.000,56.000,53.000,46.000,40.000,56.000,56.000,52.000,55.000,51.000,46.000,45.000,46.000,49.000,45.000,46.000,47.000,45.000,45.000,57.000,58.000,57.000,58.000,65.000,72.000,75.000,75.000,73.000,70.000,71.000,70.000,67.000,67.000,72.000,74.000,76.000,76.000,76.000,78.000,76.000,77.000,77.000,76.000,77.000,77.000,76.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,107.000,94.000,78.000,78.000,79.000,32.000,82.000,76.000,87.000,97.000,78.000,75.000,76.000,80.000,77.000,72.000,74.000,71.000,73.000,49.000,78.000,78.000,78.000,78.000,77.000,75.000,76.000,77.000,78.000,78.000,78.000,77.000,76.000,77.000,76.000,76.000,76.000,72.000,75.000,74.000,71.000,69.000,67.000,63.000,58.000,60.000,64.000,64.000,64.000,60.000,55.000,70.000,23.000,28.000,71.000,60.000,72.000,65.000,78.000}
-62.951 LMS_LASER_2D_RIGHT LMS2 ID=3999,time=1225719874.600937,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=88,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.964,-1.000,15.871,12.969,11.167,9.953,9.042,8.253,7.464,6.856,6.442,5.938,5.569,5.219,4.899,4.588,4.358,4.083,3.915,3.732,3.500,3.355,3.239,3.033,2.945,2.818,2.720,2.614,2.534,2.462,2.383,2.300,2.225,2.156,2.114,2.054,1.983,1.925,1.884,1.800,1.766,1.746,1.704,1.661,1.623,1.581,1.551,1.502,1.470,1.455,1.425,1.401,1.392,1.364,1.335,1.332,1.303,1.278,1.252,1.236,1.223,1.221,1.221,1.208,1.233,1.233,1.229,1.244,1.244,1.224,1.209,1.187,1.187,1.163,1.149,1.137,1.131,1.116,1.114,1.111,1.095,1.096,1.067,1.060,1.067,1.060,1.056,1.039,1.029,0.985,0.985,0.978},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,30.000,0.000,117.000,116.000,82.000,66.000,59.000,55.000,55.000,60.000,64.000,67.000,67.000,68.000,70.000,72.000,73.000,74.000,75.000,76.000,76.000,76.000,79.000,82.000,81.000,77.000,79.000,80.000,81.000,81.000,81.000,80.000,79.000,80.000,80.000,80.000,79.000,79.000,80.000,81.000,79.000,78.000,78.000,79.000,78.000,77.000,75.000,77.000,80.000,78.000,63.000,66.000,78.000,75.000,74.000,76.000,69.000,69.000,71.000,77.000,78.000,77.000,77.000,70.000,60.000,56.000,54.000,49.000,49.000,52.000,57.000,64.000,59.000,56.000,57.000,64.000,56.000,38.000,42.000,44.000,44.000,45.000,58.000,63.000,47.000,41.000,42.000,38.000,34.000,24.000,24.000,23.000}
-62.962 LMS_LASER_2D_LEFT LMS1 ID=4127,time=1225719874.608721,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=124,Range=[181]{1.028,1.046,1.049,1.059,1.067,1.080,1.084,1.092,1.115,1.117,1.123,1.132,1.144,1.155,1.172,1.181,1.192,1.209,1.227,1.234,1.256,1.263,1.284,1.293,1.313,1.330,1.357,1.365,1.387,1.407,1.435,1.453,1.475,1.508,1.526,1.555,1.579,1.607,1.644,1.663,1.688,1.732,1.756,1.788,1.827,1.858,1.895,1.937,1.973,2.010,2.043,2.089,2.147,2.213,2.258,2.321,2.342,2.384,2.482,2.555,2.663,2.707,2.724,2.714,2.735,2.875,2.960,3.037,3.104,3.202,3.283,3.471,3.615,3.738,3.872,3.967,4.061,4.065,4.061,4.085,4.116,4.128,4.136,4.130,4.138,4.148,4.133,4.152,4.194,4.229,4.226,4.231,4.253,4.255,4.256,4.270,4.281,4.264,4.265,4.274,4.267,4.275,4.283,4.276,4.294,4.293,4.304,4.306,4.304,4.320,4.329,4.339,4.346,4.348,4.367,4.375,4.381,4.391,4.402,4.420,4.436,4.443,3.338,3.402,4.473,4.494,2.838,3.030,2.870,2.815,2.827,2.942,2.721,2.664,2.628,2.608,2.592,2.530,2.527,2.634,2.724,2.928,4.779,4.791,4.815,4.846,4.875,4.896,4.925,4.941,4.970,4.998,5.025,5.050,5.081,5.125,5.151,5.184,5.220,5.243,5.275,5.307,5.334,5.367,5.395,5.437,5.467,5.489,5.516,5.550,5.524,5.568,5.649,6.618,6.690,5.450,5.423,5.437,5.491,5.559,5.562},Reflectance=[181]{49.000,41.000,47.000,48.000,43.000,41.000,43.000,43.000,45.000,42.000,46.000,46.000,48.000,46.000,46.000,46.000,47.000,47.000,43.000,47.000,44.000,48.000,49.000,49.000,47.000,45.000,45.000,50.000,48.000,46.000,46.000,51.000,52.000,52.000,52.000,53.000,56.000,54.000,46.000,51.000,54.000,46.000,49.000,55.000,49.000,53.000,55.000,54.000,55.000,56.000,59.000,58.000,52.000,42.000,41.000,43.000,57.000,55.000,49.000,41.000,56.000,56.000,52.000,56.000,63.000,53.000,46.000,46.000,52.000,51.000,57.000,45.000,49.000,56.000,54.000,58.000,62.000,59.000,64.000,70.000,74.000,75.000,72.000,70.000,70.000,68.000,65.000,67.000,72.000,75.000,76.000,75.000,76.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,99.000,103.000,78.000,78.000,25.000,111.000,77.000,76.000,75.000,95.000,113.000,119.000,94.000,82.000,81.000,70.000,64.000,73.000,70.000,106.000,77.000,78.000,78.000,78.000,77.000,76.000,77.000,77.000,77.000,78.000,78.000,77.000,76.000,77.000,77.000,76.000,76.000,70.000,74.000,73.000,70.000,70.000,67.000,63.000,59.000,64.000,65.000,63.000,63.000,61.000,51.000,31.000,21.000,34.000,67.000,66.000,69.000,63.000,75.000}
-62.974 LMS_LASER_2D_LEFT LMS1 ID=4128,time=1225719874.622057,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=125,Range=[181]{1.026,1.036,1.051,1.057,1.071,1.081,1.084,1.096,1.105,1.111,1.126,1.132,1.148,1.160,1.169,1.182,1.187,1.216,1.224,1.236,1.246,1.264,1.284,1.291,1.315,1.326,1.344,1.371,1.385,1.412,1.425,1.449,1.475,1.505,1.530,1.552,1.567,1.599,1.645,1.664,1.694,1.722,1.756,1.788,1.824,1.860,1.892,1.929,1.964,2.003,2.046,2.093,2.149,2.188,2.253,2.305,2.331,2.377,2.476,2.552,2.634,2.673,2.717,2.712,2.726,2.849,2.917,3.025,3.085,3.180,3.266,3.294,3.353,3.716,3.865,3.985,4.053,4.053,4.053,4.081,4.110,4.125,4.140,4.133,4.127,4.146,4.124,4.144,4.184,4.219,4.224,4.222,4.253,4.255,4.255,4.262,4.260,4.249,4.257,4.266,4.267,4.275,4.278,4.278,4.286,4.287,4.296,4.306,4.306,4.324,4.329,4.330,4.340,4.349,4.358,4.374,4.383,4.392,4.403,4.410,4.427,4.435,3.380,3.308,4.476,4.484,4.494,2.931,3.025,2.859,2.830,2.785,2.501,2.466,2.944,2.706,2.484,2.510,2.571,2.709,2.906,2.917,2.839,4.791,4.805,4.837,4.859,4.890,4.912,4.941,4.963,4.989,5.017,5.040,5.067,5.109,5.142,5.176,5.200,5.242,5.270,5.290,5.320,5.356,5.393,5.428,5.474,5.495,5.507,5.544,5.524,5.541,5.720,6.614,6.652,5.465,5.428,5.412,5.454,5.585,5.595},Reflectance=[181]{48.000,44.000,43.000,42.000,46.000,45.000,43.000,46.000,41.000,44.000,43.000,45.000,45.000,43.000,48.000,46.000,49.000,45.000,46.000,48.000,48.000,49.000,50.000,49.000,48.000,49.000,49.000,49.000,51.000,48.000,50.000,52.000,49.000,51.000,54.000,52.000,55.000,50.000,42.000,47.000,48.000,49.000,52.000,47.000,51.000,51.000,49.000,54.000,55.000,56.000,57.000,55.000,50.000,48.000,36.000,44.000,60.000,56.000,50.000,39.000,60.000,69.000,57.000,58.000,65.000,57.000,57.000,48.000,51.000,54.000,57.000,69.000,64.000,54.000,47.000,59.000,65.000,64.000,65.000,69.000,72.000,74.000,73.000,71.000,70.000,70.000,65.000,67.000,72.000,74.000,76.000,75.000,76.000,77.000,77.000,76.000,76.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,99.000,18.000,78.000,78.000,78.000,29.000,99.000,76.000,75.000,113.000,53.000,31.000,112.000,82.000,74.000,72.000,74.000,94.000,109.000,96.000,27.000,78.000,77.000,78.000,78.000,77.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,76.000,76.000,75.000,75.000,73.000,69.000,69.000,67.000,63.000,58.000,60.000,65.000,67.000,63.000,61.000,49.000,32.000,27.000,69.000,62.000,67.000,64.000,63.000,61.000}
-62.974 LMS_LASER_2D_RIGHT LMS2 ID=4000,time=1225719874.614281,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=89,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.301,-1.000,16.169,13.081,11.254,10.004,9.126,8.322,7.545,6.918,6.458,5.955,5.578,5.219,4.926,4.638,4.367,4.102,3.925,3.730,3.525,3.375,3.242,3.063,2.969,2.828,2.728,2.626,2.532,2.479,2.388,2.283,2.215,2.153,2.116,2.070,1.990,1.933,1.875,1.790,1.765,1.750,1.709,1.660,1.612,1.575,1.544,1.516,1.472,1.457,1.428,1.405,1.393,1.379,1.341,1.322,1.302,1.279,1.262,1.244,1.233,1.224,1.220,1.209,1.230,1.222,1.207,1.221,1.213,1.200,1.198,1.190,1.178,1.150,1.149,1.142,1.143,1.125,1.105,1.110,1.104,1.082,1.068,1.061,1.066,1.068,1.054,1.044,0.999,0.993,0.978,0.983},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,0.000,107.000,121.000,83.000,68.000,58.000,55.000,55.000,59.000,64.000,67.000,67.000,69.000,70.000,71.000,73.000,74.000,75.000,76.000,75.000,77.000,80.000,80.000,81.000,77.000,79.000,80.000,80.000,81.000,80.000,80.000,79.000,79.000,81.000,80.000,79.000,79.000,80.000,81.000,78.000,76.000,77.000,78.000,78.000,77.000,76.000,70.000,78.000,76.000,68.000,73.000,78.000,77.000,72.000,70.000,66.000,72.000,74.000,76.000,78.000,78.000,77.000,72.000,63.000,65.000,67.000,64.000,64.000,72.000,69.000,56.000,55.000,57.000,57.000,53.000,54.000,38.000,42.000,44.000,45.000,49.000,62.000,65.000,50.000,44.000,42.000,37.000,28.000,25.000,23.000,24.000}
-62.986 LMS_LASER_2D_LEFT LMS1 ID=4129,time=1225719874.635392,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=126,Range=[181]{1.021,1.041,1.050,1.055,1.067,1.077,1.080,1.092,1.100,1.115,1.129,1.139,1.151,1.160,1.170,1.186,1.199,1.209,1.217,1.238,1.253,1.262,1.282,1.295,1.318,1.325,1.347,1.358,1.384,1.399,1.417,1.444,1.473,1.504,1.526,1.555,1.578,1.610,1.638,1.663,1.689,1.719,1.750,1.781,1.812,1.849,1.878,1.929,1.964,1.998,2.037,2.078,2.149,2.188,2.248,2.295,2.329,2.357,2.473,2.530,2.638,2.675,2.691,2.707,2.718,2.826,2.933,3.009,3.088,3.152,3.272,3.416,3.473,3.311,3.419,3.996,4.042,4.043,4.035,4.066,4.104,4.117,4.128,4.124,4.119,4.143,4.120,4.134,4.175,4.216,4.225,4.223,4.245,4.253,4.252,4.251,4.249,4.251,4.258,4.264,4.260,4.270,4.270,4.278,4.278,4.283,4.295,4.295,4.294,4.306,4.321,4.331,4.346,4.347,4.350,4.366,4.372,4.393,4.392,4.411,4.419,4.428,4.434,4.457,4.465,4.476,3.008,3.028,2.931,2.920,2.821,2.472,2.433,2.454,2.574,2.605,2.483,2.494,2.575,2.649,2.771,2.840,2.887,4.781,4.807,4.833,4.854,4.882,4.908,4.934,4.960,4.980,5.007,5.034,5.059,5.096,5.133,5.170,5.196,5.234,5.261,5.284,5.312,5.346,5.379,5.428,5.469,5.498,5.505,5.550,5.530,5.518,5.718,6.513,5.472,5.455,5.437,5.465,5.454,5.509,5.558},Reflectance=[181]{54.000,51.000,38.000,41.000,43.000,44.000,46.000,43.000,47.000,46.000,44.000,40.000,43.000,43.000,44.000,43.000,45.000,47.000,47.000,44.000,47.000,48.000,44.000,46.000,44.000,52.000,54.000,51.000,50.000,50.000,50.000,54.000,51.000,54.000,49.000,49.000,52.000,41.000,43.000,51.000,50.000,47.000,50.000,48.000,50.000,54.000,55.000,54.000,55.000,54.000,57.000,56.000,49.000,48.000,37.000,43.000,55.000,56.000,52.000,46.000,54.000,67.000,64.000,60.000,66.000,54.000,49.000,50.000,49.000,53.000,55.000,63.000,67.000,69.000,58.000,59.000,71.000,64.000,67.000,70.000,73.000,75.000,72.000,71.000,70.000,72.000,68.000,69.000,72.000,73.000,76.000,75.000,76.000,76.000,76.000,76.000,78.000,78.000,78.000,77.000,78.000,79.000,79.000,79.000,78.000,79.000,80.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,33.000,83.000,77.000,76.000,75.000,80.000,74.000,75.000,94.000,78.000,69.000,69.000,72.000,59.000,53.000,34.000,14.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,76.000,76.000,77.000,77.000,75.000,75.000,74.000,69.000,69.000,68.000,63.000,59.000,57.000,60.000,61.000,60.000,58.000,52.000,38.000,22.000,69.000,63.000,74.000,63.000,67.000,69.000}
-62.986 LMS_LASER_2D_RIGHT LMS2 ID=4001,time=1225719874.627624,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=90,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.265,26.449,16.438,13.276,11.478,10.134,9.204,8.350,7.573,6.929,6.504,6.008,5.629,5.264,4.954,4.654,4.395,4.134,3.928,3.753,3.537,3.376,3.242,3.095,2.983,2.839,2.732,2.626,2.543,2.477,2.397,2.300,2.206,2.145,2.115,2.078,2.006,1.933,1.875,1.789,1.766,1.741,1.708,1.656,1.607,1.577,1.559,1.536,1.484,1.460,1.432,1.416,1.393,1.380,1.350,1.338,1.304,1.289,1.263,1.247,1.237,1.221,1.216,1.216,1.230,1.221,1.208,1.208,1.199,1.192,1.192,1.191,1.172,1.152,1.150,1.141,1.138,1.124,1.112,1.102,1.102,1.074,1.062,1.053,1.073,1.062,1.055,1.039,1.001,0.987,0.978,0.987},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,3.000,102.000,123.000,86.000,71.000,58.000,56.000,56.000,60.000,64.000,68.000,67.000,69.000,70.000,70.000,73.000,74.000,73.000,75.000,75.000,78.000,80.000,79.000,80.000,78.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,79.000,81.000,80.000,79.000,79.000,80.000,80.000,79.000,79.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,78.000,74.000,71.000,67.000,69.000,72.000,74.000,75.000,77.000,77.000,75.000,70.000,59.000,63.000,70.000,69.000,69.000,72.000,71.000,61.000,56.000,54.000,53.000,53.000,48.000,38.000,42.000,44.000,41.000,53.000,66.000,66.000,50.000,45.000,40.000,35.000,27.000,25.000,24.000,23.000}
-62.999 LMS_LASER_2D_RIGHT LMS2 ID=4002,time=1225719874.640967,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=91,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.282,26.431,16.718,13.494,11.617,10.179,9.273,8.407,7.619,6.978,6.545,6.043,5.663,5.300,4.990,4.688,4.421,4.177,3.972,3.769,3.565,3.396,3.264,3.113,2.999,2.860,2.741,2.635,2.560,2.487,2.406,2.318,2.218,2.148,2.123,2.084,1.998,1.933,1.860,1.812,1.776,1.749,1.706,1.662,1.622,1.584,1.558,1.529,1.485,1.463,1.445,1.426,1.396,1.379,1.360,1.325,1.305,1.296,1.271,1.253,1.237,1.229,1.218,1.216,1.227,1.230,1.213,1.200,1.192,1.191,1.192,1.188,1.173,1.154,1.152,1.144,1.147,1.132,1.111,1.107,1.094,1.066,1.055,1.060,1.069,1.062,1.057,1.045,0.996,0.984,0.985,0.989},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,9.000,5.000,93.000,125.000,88.000,73.000,58.000,57.000,56.000,57.000,64.000,67.000,67.000,69.000,70.000,70.000,72.000,73.000,73.000,75.000,76.000,75.000,79.000,79.000,80.000,79.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,81.000,79.000,79.000,79.000,81.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,73.000,77.000,74.000,71.000,72.000,73.000,74.000,77.000,77.000,76.000,70.000,58.000,59.000,65.000,72.000,71.000,70.000,71.000,65.000,56.000,59.000,58.000,54.000,52.000,42.000,39.000,42.000,44.000,61.000,67.000,64.000,48.000,45.000,41.000,37.000,27.000,25.000,24.000,21.000}
-63.007 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.1801,19.4290,-0.8714},Vel=[3x1]{-0.8950,-0.7530,12.5641},Raw=[2x1]{21.3024,-0.8714},time=1225719874.65437579154968,Speed=1.16965041908823,Pitch=0.02692024480606,Roll=0.03589365974142,PitchDot=0.02019018360455,RollDot=-0.00049353782144
-63.007 ODOMETRY_POSE iPlatform Pose=[3x1]{5.1801,19.4290,-0.8707},Vel=[3x1]{-0.8950,-0.7530,-0.0023},Raw=[2x1]{21.3024,-0.8714},time=1225719874.6544,Speed=1.1697,Pitch=-0.0101,Roll=0.0437,PitchDot=0.0202,RollDot=-0.0004
-63.015 LMS_LASER_2D_RIGHT LMS2 ID=4003,time=1225719874.654313,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=92,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.367,17.060,14.062,11.905,10.380,9.436,8.548,7.692,7.055,6.606,6.110,5.715,5.345,5.016,4.723,4.465,4.203,3.991,3.797,3.584,3.437,3.266,3.128,3.005,2.869,2.779,2.655,2.570,2.507,2.426,2.328,2.246,2.168,2.132,2.078,2.007,1.951,1.884,1.819,1.786,1.760,1.715,1.662,1.624,1.591,1.554,1.515,1.489,1.464,1.445,1.417,1.394,1.377,1.364,1.335,1.313,1.295,1.273,1.252,1.239,1.232,1.219,1.216,1.233,1.229,1.233,1.205,1.200,1.191,1.182,1.182,1.179,1.159,1.153,1.150,1.145,1.136,1.126,1.102,1.083,1.062,1.061,1.071,1.074,1.067,1.059,1.045,0.998,0.991,0.985,0.989},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,7.000,85.000,117.000,92.000,75.000,59.000,57.000,57.000,58.000,64.000,67.000,66.000,69.000,70.000,70.000,71.000,73.000,74.000,75.000,77.000,76.000,79.000,78.000,79.000,79.000,80.000,81.000,81.000,81.000,81.000,80.000,80.000,81.000,81.000,80.000,76.000,79.000,80.000,78.000,79.000,79.000,79.000,79.000,79.000,77.000,76.000,75.000,78.000,78.000,78.000,75.000,69.000,70.000,75.000,74.000,71.000,70.000,74.000,76.000,77.000,78.000,76.000,70.000,60.000,54.000,52.000,65.000,71.000,70.000,71.000,69.000,59.000,61.000,63.000,61.000,55.000,51.000,43.000,43.000,54.000,66.000,65.000,56.000,46.000,43.000,41.000,35.000,25.000,24.000,24.000,22.000}
-63.023 DESIRED_THRUST iJoystick 84.5393230995
-63.023 DESIRED_RUDDER iJoystick 3.09152500992
-63.010 LMS_LASER_2D_LEFT LMS1 ID=4130,time=1225719874.648737,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=127,Range=[181]{1.027,1.030,1.043,1.056,1.064,1.072,1.084,1.094,1.096,1.111,1.124,1.129,1.145,1.156,1.167,1.182,1.200,1.205,1.225,1.237,1.241,1.270,1.270,1.285,1.308,1.328,1.337,1.364,1.387,1.402,1.417,1.442,1.441,1.470,1.520,1.543,1.568,1.604,1.636,1.662,1.684,1.698,1.732,1.775,1.805,1.841,1.880,1.920,1.946,1.987,2.025,2.074,2.137,2.181,2.231,2.292,2.342,2.406,2.465,2.517,2.634,2.682,2.704,2.718,2.733,2.850,2.927,3.009,3.077,3.149,3.238,3.391,3.446,3.388,3.397,3.953,4.039,4.042,4.033,4.057,4.095,4.110,4.121,4.119,4.125,4.142,4.125,4.135,4.172,4.208,4.223,4.218,4.242,4.243,4.242,4.248,4.249,4.255,4.252,4.259,4.252,4.270,4.260,4.269,4.278,4.278,4.279,4.286,4.294,4.305,4.314,4.321,4.337,4.341,4.348,4.356,4.374,4.381,4.394,4.408,4.409,4.435,4.441,4.448,4.466,4.476,3.026,3.148,2.999,2.836,2.784,2.595,2.536,2.465,2.463,2.504,2.497,2.488,2.500,2.527,2.786,2.847,4.757,4.776,4.799,4.828,4.846,4.876,4.899,4.926,4.952,4.972,5.007,5.035,5.057,5.082,5.115,5.157,5.194,5.227,5.253,5.278,5.309,5.342,5.374,5.419,5.455,5.493,5.500,5.551,5.533,5.514,5.673,6.386,6.446,5.529,5.454,5.426,5.485,5.462,5.552},Reflectance=[181]{49.000,50.000,44.000,45.000,46.000,41.000,43.000,44.000,46.000,48.000,45.000,44.000,44.000,45.000,47.000,46.000,42.000,44.000,42.000,43.000,46.000,42.000,47.000,46.000,44.000,50.000,53.000,53.000,51.000,51.000,54.000,53.000,64.000,58.000,49.000,52.000,51.000,49.000,40.000,41.000,48.000,54.000,54.000,49.000,54.000,55.000,51.000,54.000,58.000,57.000,59.000,54.000,48.000,44.000,42.000,42.000,46.000,46.000,49.000,49.000,52.000,57.000,59.000,53.000,56.000,50.000,46.000,46.000,48.000,52.000,52.000,54.000,59.000,65.000,63.000,52.000,68.000,69.000,66.000,70.000,73.000,75.000,73.000,70.000,72.000,71.000,69.000,69.000,70.000,73.000,75.000,74.000,76.000,76.000,76.000,75.000,78.000,79.000,78.000,78.000,78.000,80.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,76.000,78.000,79.000,78.000,16.000,111.000,108.000,94.000,72.000,82.000,100.000,78.000,75.000,77.000,75.000,75.000,74.000,61.000,97.000,18.000,78.000,79.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,76.000,76.000,76.000,76.000,76.000,76.000,75.000,71.000,70.000,67.000,61.000,58.000,59.000,58.000,57.000,62.000,60.000,58.000,54.000,50.000,70.000,64.000,68.000,67.000,66.000,81.000}
-63.015 LMS_LASER_2D_RIGHT LMS2 ID=4004,time=1225719874.667646,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=93,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.261,17.491,14.436,12.150,10.546,9.570,8.706,7.872,7.148,6.687,6.200,5.785,5.398,5.059,4.766,4.500,4.256,4.010,3.822,3.628,3.457,3.307,3.156,3.018,2.890,2.797,2.671,2.578,2.516,2.427,2.336,2.264,2.194,2.133,2.070,2.022,1.944,1.898,1.830,1.797,1.753,1.725,1.670,1.633,1.603,1.544,1.509,1.490,1.479,1.451,1.423,1.394,1.377,1.368,1.341,1.322,1.286,1.274,1.262,1.241,1.233,1.226,1.217,1.228,1.235,1.250,1.220,1.199,1.191,1.182,1.181,1.184,1.170,1.154,1.145,1.136,1.137,1.117,1.099,1.084,1.069,1.080,1.080,1.076,1.065,1.060,1.046,1.022,0.987,0.990,0.987},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,11.000,71.000,116.000,97.000,77.000,61.000,56.000,57.000,56.000,63.000,67.000,66.000,68.000,70.000,72.000,71.000,73.000,74.000,75.000,76.000,77.000,78.000,78.000,80.000,80.000,81.000,81.000,80.000,81.000,81.000,80.000,80.000,81.000,81.000,80.000,78.000,80.000,79.000,79.000,80.000,80.000,79.000,79.000,78.000,78.000,71.000,73.000,78.000,78.000,77.000,74.000,69.000,70.000,71.000,71.000,70.000,68.000,75.000,76.000,78.000,78.000,76.000,72.000,62.000,53.000,48.000,62.000,69.000,69.000,71.000,68.000,61.000,63.000,66.000,63.000,58.000,51.000,36.000,41.000,54.000,63.000,56.000,49.000,44.000,42.000,44.000,37.000,31.000,25.000,25.000,23.000}
-63.022 LMS_LASER_2D_LEFT LMS1 ID=4131,time=1225719874.662081,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=128,Range=[181]{1.035,1.039,1.040,1.055,1.061,1.074,1.079,1.093,1.100,1.115,1.122,1.131,1.141,1.153,1.171,1.181,1.191,1.196,1.212,1.229,1.239,1.254,1.269,1.281,1.301,1.316,1.341,1.362,1.375,1.395,1.422,1.440,1.441,1.459,1.517,1.546,1.566,1.592,1.627,1.644,1.681,1.698,1.736,1.769,1.800,1.831,1.871,1.911,1.939,1.977,2.018,2.055,2.126,2.176,2.226,2.281,2.326,2.392,2.459,2.527,2.611,2.692,2.712,2.717,2.730,2.829,2.899,2.993,3.065,3.135,3.247,3.341,3.505,3.442,3.442,3.933,4.024,4.040,4.032,4.042,4.088,4.111,4.125,4.117,4.119,4.130,4.117,4.120,4.158,4.196,4.220,4.214,4.233,4.244,4.245,4.243,4.240,4.248,4.248,4.258,4.252,4.252,4.260,4.269,4.274,4.272,4.279,4.287,4.285,4.304,4.314,4.313,4.332,4.344,4.341,4.358,4.365,4.383,4.383,4.394,4.409,4.420,4.435,4.444,4.457,4.464,4.485,4.493,4.507,2.925,2.872,2.975,4.564,2.607,2.542,2.515,2.474,2.453,2.572,2.561,2.887,4.733,4.751,4.767,4.792,4.817,4.840,4.867,4.889,4.916,4.934,4.963,4.989,5.024,5.048,5.074,5.107,5.150,5.186,5.211,5.246,5.266,5.300,5.323,5.365,5.408,5.443,5.479,5.495,5.548,5.542,5.506,5.602,6.139,6.341,5.782,5.491,5.437,5.545,5.516,5.653},Reflectance=[181]{40.000,42.000,42.000,37.000,40.000,42.000,46.000,48.000,42.000,41.000,46.000,45.000,41.000,44.000,40.000,41.000,42.000,49.000,44.000,44.000,44.000,48.000,47.000,48.000,49.000,48.000,47.000,52.000,50.000,51.000,52.000,52.000,63.000,62.000,52.000,53.000,54.000,46.000,47.000,46.000,46.000,54.000,51.000,46.000,52.000,54.000,51.000,54.000,59.000,56.000,56.000,58.000,51.000,46.000,44.000,40.000,50.000,43.000,45.000,44.000,50.000,49.000,51.000,53.000,55.000,48.000,49.000,50.000,50.000,50.000,53.000,51.000,52.000,64.000,69.000,58.000,69.000,70.000,71.000,71.000,74.000,75.000,74.000,72.000,72.000,70.000,69.000,70.000,71.000,72.000,75.000,75.000,76.000,76.000,76.000,76.000,78.000,77.000,77.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,111.000,87.000,109.000,78.000,132.000,97.000,78.000,78.000,72.000,101.000,56.000,116.000,78.000,78.000,78.000,78.000,78.000,79.000,77.000,76.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,77.000,76.000,76.000,74.000,71.000,70.000,65.000,60.000,60.000,60.000,59.000,56.000,58.000,61.000,60.000,68.000,63.000,82.000,74.000,64.000,67.000,63.000,75.000}
-63.030 LMS_LASER_2D_RIGHT LMS2 ID=4005,time=1225719874.680979,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=94,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.603,18.127,15.076,12.550,10.733,9.684,8.837,8.039,7.286,6.758,6.305,5.850,5.485,5.112,4.817,4.552,4.300,4.058,3.861,3.669,3.491,3.332,3.174,3.023,2.916,2.813,2.699,2.597,2.525,2.445,2.355,2.274,2.210,2.150,2.096,2.034,1.959,1.918,1.848,1.806,1.770,1.724,1.677,1.634,1.611,1.552,1.519,1.513,1.481,1.457,1.441,1.410,1.394,1.368,1.341,1.323,1.295,1.271,1.259,1.248,1.231,1.220,1.215,1.230,1.240,1.252,1.228,1.199,1.192,1.183,1.182,1.180,1.173,1.149,1.132,1.138,1.127,1.119,1.110,1.104,1.090,1.091,1.090,1.077,1.075,1.059,1.050,1.048,1.008,0.987,0.983},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,38.000,33.000,120.000,103.000,81.000,63.000,57.000,56.000,56.000,62.000,66.000,66.000,68.000,69.000,70.000,71.000,72.000,74.000,74.000,76.000,76.000,78.000,78.000,79.000,80.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,81.000,80.000,79.000,79.000,80.000,79.000,80.000,80.000,79.000,78.000,79.000,78.000,69.000,74.000,77.000,78.000,79.000,77.000,75.000,70.000,71.000,72.000,72.000,70.000,74.000,75.000,77.000,78.000,77.000,75.000,64.000,55.000,48.000,58.000,69.000,71.000,72.000,70.000,66.000,67.000,69.000,70.000,60.000,54.000,41.000,41.000,40.000,30.000,38.000,42.000,44.000,43.000,44.000,43.000,42.000,30.000,25.000,24.000}
-63.035 LMS_LASER_2D_LEFT LMS1 ID=4132,time=1225719874.675425,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=129,Range=[181]{1.037,1.043,1.048,1.054,1.067,1.073,1.078,1.088,1.112,1.110,1.120,1.125,1.135,1.151,1.154,1.174,1.182,1.195,1.211,1.227,1.238,1.258,1.264,1.287,1.298,1.320,1.332,1.351,1.369,1.394,1.416,1.425,1.460,1.477,1.512,1.538,1.556,1.581,1.622,1.653,1.672,1.703,1.723,1.760,1.803,1.834,1.861,1.910,1.909,1.958,2.007,2.046,2.100,2.158,2.203,2.273,2.330,2.381,2.435,2.513,2.591,2.670,2.718,2.712,2.723,2.794,2.875,2.977,3.063,3.130,3.227,3.310,3.439,3.433,3.626,3.911,3.999,4.031,4.023,4.042,4.074,4.099,4.107,4.113,4.107,4.121,4.114,4.122,4.147,4.179,4.212,4.207,4.223,4.233,4.236,4.230,4.238,4.248,4.245,4.249,4.252,4.258,4.255,4.259,4.260,4.269,4.278,4.278,4.279,4.293,4.304,4.312,4.320,4.331,4.331,4.347,4.355,4.372,4.375,4.394,4.403,4.420,4.428,4.436,4.446,4.458,4.471,4.483,4.498,3.062,4.533,4.546,3.051,2.569,2.468,2.493,2.451,2.436,2.602,2.699,2.840,4.726,4.742,4.757,4.784,4.799,4.827,4.859,4.882,4.908,4.924,4.954,4.979,5.009,5.031,5.070,5.099,5.135,5.166,5.202,5.237,5.257,5.286,5.322,5.345,5.383,5.419,5.463,5.481,5.527,5.555,5.511,5.550,5.868,6.185,6.246,5.700,5.512,5.578,5.507,5.632},Reflectance=[181]{40.000,39.000,42.000,41.000,39.000,42.000,44.000,40.000,40.000,38.000,44.000,47.000,48.000,43.000,49.000,45.000,50.000,48.000,43.000,43.000,44.000,45.000,49.000,47.000,48.000,46.000,47.000,48.000,48.000,51.000,53.000,54.000,54.000,53.000,50.000,50.000,54.000,53.000,44.000,45.000,47.000,48.000,54.000,50.000,46.000,51.000,51.000,50.000,65.000,55.000,58.000,57.000,55.000,50.000,46.000,41.000,43.000,45.000,47.000,42.000,53.000,51.000,50.000,51.000,55.000,56.000,57.000,50.000,49.000,48.000,48.000,49.000,51.000,61.000,53.000,60.000,71.000,75.000,71.000,71.000,72.000,75.000,74.000,71.000,72.000,70.000,69.000,73.000,73.000,73.000,75.000,76.000,75.000,76.000,76.000,77.000,77.000,77.000,76.000,78.000,78.000,80.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,77.000,110.000,77.000,78.000,26.000,114.000,74.000,76.000,75.000,70.000,105.000,41.000,34.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,76.000,77.000,77.000,76.000,76.000,76.000,74.000,72.000,72.000,69.000,63.000,64.000,63.000,61.000,51.000,55.000,59.000,62.000,74.000,66.000,67.000,81.000,70.000,69.000,63.000,74.000}
-63.043 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.2157,19.4587,-0.8786},Vel=[3x1]{-0.9049,-0.7503,15.8974},Raw=[2x1]{21.3488,-0.8786},time=1225719874.69038176536560,Speed=1.17549136999504,Pitch=0.02916359853990,Roll=0.03365030600758,PitchDot=0.03813701347526,RollDot=-0.00123384455361
-63.043 ODOMETRY_POSE iPlatform Pose=[3x1]{5.2157,19.4587,-0.8779},Vel=[3x1]{-0.9049,-0.7503,-2.9520},Raw=[2x1]{21.3488,-0.8786},time=1225719874.6904,Speed=1.1755,Pitch=-0.0073,Roll=0.0439,PitchDot=-0.0372,RollDot=0.0084
-63.047 DESIRED_THRUST iJoystick 84.5393230995
-63.047 DESIRED_RUDDER iJoystick 3.09152500992
-63.041 LMS_LASER_2D_RIGHT LMS2 ID=4006,time=1225719874.694311,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=95,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.575,18.296,15.540,12.807,10.972,9.866,8.994,8.196,7.403,6.844,6.400,5.921,5.544,5.165,4.872,4.596,4.330,4.108,3.902,3.706,3.511,3.365,3.200,3.045,2.932,2.834,2.724,2.615,2.534,2.463,2.382,2.293,2.228,2.167,2.116,2.053,1.977,1.936,1.866,1.815,1.779,1.732,1.688,1.653,1.616,1.563,1.535,1.520,1.492,1.464,1.438,1.432,1.405,1.369,1.333,1.314,1.296,1.287,1.266,1.246,1.231,1.224,1.223,1.223,1.238,1.235,1.244,1.212,1.198,1.175,1.189,1.184,1.179,1.151,1.148,1.144,1.133,1.117,1.104,1.100,1.060,1.094,1.085,1.084,1.067,1.063,1.059,1.040,1.040,0.982,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,38.000,5.000,118.000,108.000,83.000,66.000,57.000,56.000,55.000,62.000,65.000,67.000,68.000,70.000,70.000,71.000,72.000,73.000,74.000,76.000,77.000,77.000,78.000,78.000,80.000,81.000,81.000,81.000,81.000,81.000,81.000,81.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,73.000,72.000,77.000,79.000,78.000,78.000,76.000,74.000,71.000,74.000,76.000,71.000,71.000,75.000,77.000,78.000,78.000,75.000,67.000,58.000,53.000,53.000,63.000,69.000,71.000,66.000,61.000,64.000,73.000,68.000,58.000,53.000,41.000,39.000,38.000,27.000,35.000,39.000,41.000,41.000,42.000,39.000,38.000,38.000,26.000,24.000}
-63.046 LMS_LASER_2D_LEFT LMS1 ID=4133,time=1225719874.688766,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=130,Range=[181]{1.022,1.043,1.042,1.054,1.055,1.064,1.080,1.089,1.095,1.107,1.109,1.123,1.134,1.148,1.165,1.178,1.178,1.201,1.207,1.214,1.233,1.251,1.268,1.278,1.290,1.310,1.328,1.347,1.364,1.391,1.408,1.425,1.442,1.479,1.503,1.525,1.558,1.578,1.610,1.642,1.669,1.680,1.717,1.756,1.789,1.823,1.848,1.893,1.892,1.927,2.004,2.036,2.091,2.150,2.198,2.254,2.309,2.366,2.433,2.499,2.586,2.660,2.711,2.707,2.701,2.781,2.882,2.960,3.008,3.123,3.224,3.305,3.379,3.424,3.785,3.880,3.972,4.031,4.018,4.031,4.060,4.098,4.102,4.110,4.100,4.116,4.120,4.112,4.134,4.173,4.203,4.207,4.215,4.234,4.230,4.231,4.238,4.248,4.250,4.242,4.244,4.243,4.253,4.252,4.259,4.259,4.269,4.269,4.269,4.285,4.295,4.299,4.317,4.321,4.330,4.340,4.346,4.362,4.375,4.388,4.394,4.402,4.420,4.426,4.445,4.448,4.459,4.476,4.493,4.511,2.568,2.628,2.577,2.585,2.538,2.600,2.485,2.495,2.555,4.668,4.690,4.715,4.732,4.751,4.775,4.792,4.817,4.844,4.866,4.891,4.915,4.945,4.971,5.000,5.020,5.055,5.090,5.124,5.158,5.185,5.230,5.246,5.278,5.306,5.345,5.369,5.410,5.445,5.481,5.504,5.544,5.516,5.507,5.783,6.152,6.199,6.227,5.636,5.481,5.512,5.706},Reflectance=[181]{34.000,39.000,43.000,41.000,38.000,46.000,41.000,41.000,44.000,46.000,43.000,46.000,47.000,46.000,45.000,39.000,48.000,42.000,46.000,49.000,46.000,46.000,46.000,51.000,48.000,50.000,50.000,50.000,49.000,53.000,53.000,54.000,53.000,54.000,53.000,51.000,51.000,52.000,47.000,46.000,49.000,54.000,54.000,49.000,42.000,51.000,54.000,50.000,69.000,61.000,57.000,60.000,54.000,54.000,48.000,49.000,45.000,44.000,45.000,39.000,42.000,47.000,50.000,49.000,57.000,53.000,56.000,62.000,56.000,49.000,45.000,51.000,64.000,61.000,45.000,58.000,69.000,75.000,74.000,70.000,73.000,74.000,75.000,72.000,72.000,72.000,70.000,73.000,72.000,73.000,75.000,76.000,75.000,76.000,77.000,78.000,77.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,79.000,79.000,78.000,78.000,78.000,47.000,119.000,98.000,97.000,83.000,84.000,72.000,75.000,58.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,76.000,76.000,77.000,76.000,76.000,76.000,76.000,74.000,72.000,73.000,71.000,67.000,64.000,64.000,63.000,59.000,58.000,61.000,62.000,69.000,72.000,75.000,73.000,81.000,66.000,68.000,79.000}
-63.054 LMS_LASER_2D_RIGHT LMS2 ID=4007,time=1225719874.707642,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=96,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.415,-1.000,16.129,13.031,11.266,10.055,9.135,8.310,7.517,6.922,6.458,5.973,5.596,5.220,4.917,4.630,4.384,4.169,3.929,3.733,3.530,3.386,3.218,3.078,2.943,2.860,2.725,2.627,2.543,2.471,2.383,2.302,2.239,2.177,2.123,2.061,1.999,1.938,1.866,1.824,1.779,1.740,1.698,1.668,1.625,1.590,1.545,1.535,1.513,1.465,1.438,1.425,1.399,1.378,1.358,1.322,1.302,1.287,1.262,1.246,1.233,1.225,1.219,1.224,1.234,1.238,1.247,1.218,1.205,1.191,1.197,1.189,1.177,1.162,1.163,1.157,1.149,1.124,1.114,1.107,1.086,1.079,1.086,1.086,1.068,1.069,1.053,1.043,1.036,1.002,0.981},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,0.000,102.000,117.000,86.000,68.000,58.000,57.000,55.000,61.000,65.000,67.000,67.000,70.000,70.000,71.000,72.000,72.000,74.000,77.000,77.000,78.000,78.000,77.000,81.000,81.000,81.000,81.000,81.000,81.000,81.000,81.000,81.000,81.000,81.000,80.000,79.000,81.000,80.000,80.000,80.000,79.000,79.000,78.000,79.000,77.000,76.000,79.000,77.000,71.000,70.000,77.000,75.000,72.000,70.000,70.000,67.000,69.000,73.000,77.000,78.000,78.000,77.000,68.000,61.000,54.000,51.000,57.000,64.000,69.000,60.000,60.000,62.000,64.000,59.000,53.000,46.000,38.000,42.000,40.000,31.000,30.000,35.000,42.000,44.000,44.000,39.000,39.000,35.000,29.000,25.000}
-63.058 LMS_LASER_2D_LEFT LMS1 ID=4134,time=1225719874.702106,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=131,Range=[181]{1.024,1.032,1.047,1.054,1.063,1.070,1.078,1.090,1.090,1.108,1.108,1.134,1.134,1.153,1.156,1.173,1.180,1.185,1.208,1.219,1.228,1.244,1.259,1.277,1.295,1.308,1.331,1.337,1.362,1.383,1.401,1.417,1.444,1.469,1.492,1.530,1.552,1.580,1.607,1.638,1.656,1.694,1.715,1.744,1.786,1.823,1.848,1.878,1.912,1.893,1.991,2.035,2.067,2.120,2.172,2.240,2.302,2.359,2.420,2.479,2.571,2.658,2.699,2.707,2.698,2.754,2.885,2.948,3.015,3.114,3.219,3.302,3.390,3.586,3.742,3.857,3.997,4.024,4.017,4.020,4.057,4.089,4.102,4.099,4.105,4.104,4.122,4.102,4.124,4.169,4.187,4.197,4.205,4.226,4.225,4.232,4.231,4.231,4.237,4.241,4.243,4.243,4.243,4.252,4.253,4.258,4.267,4.269,4.268,4.274,4.293,4.293,4.300,4.312,4.323,4.339,4.345,4.353,4.367,4.376,4.385,4.394,4.403,4.421,4.438,4.448,4.459,4.466,4.482,2.765,2.663,2.527,2.509,2.517,2.517,2.511,2.485,2.528,2.666,2.707,4.681,4.700,4.725,4.742,4.768,4.791,4.815,4.837,4.857,4.884,4.907,4.935,4.962,4.979,5.013,5.047,5.072,5.108,5.139,5.173,5.213,5.238,5.271,5.298,5.325,5.364,5.392,5.437,5.463,5.472,5.533,5.516,5.498,5.665,6.148,6.206,6.249,5.618,5.462,5.521,5.707},Reflectance=[181]{43.000,47.000,45.000,41.000,41.000,44.000,37.000,45.000,42.000,42.000,47.000,38.000,43.000,39.000,41.000,41.000,40.000,48.000,45.000,43.000,48.000,47.000,45.000,46.000,46.000,49.000,51.000,49.000,49.000,50.000,54.000,54.000,54.000,54.000,49.000,46.000,48.000,44.000,46.000,43.000,48.000,48.000,49.000,47.000,41.000,42.000,54.000,55.000,54.000,67.000,55.000,56.000,59.000,55.000,52.000,41.000,42.000,44.000,44.000,43.000,40.000,46.000,49.000,49.000,56.000,57.000,50.000,56.000,59.000,49.000,48.000,50.000,54.000,48.000,45.000,55.000,60.000,71.000,69.000,67.000,72.000,74.000,75.000,72.000,71.000,71.000,71.000,73.000,71.000,72.000,72.000,75.000,75.000,76.000,78.000,78.000,78.000,78.000,77.000,75.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,122.000,90.000,76.000,76.000,76.000,76.000,77.000,72.000,74.000,91.000,37.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,76.000,76.000,77.000,76.000,76.000,74.000,74.000,73.000,73.000,70.000,69.000,65.000,62.000,64.000,65.000,65.000,65.000,64.000,67.000,70.000,74.000,73.000,83.000,66.000,75.000,84.000}
-63.071 DESIRED_THRUST iJoystick 84.5393230995
-63.071 DESIRED_RUDDER iJoystick 3.09152500992
-63.079 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.2428,19.4810,-0.8843},Vel=[3x1]{-0.8934,-0.7321,11.9231},Raw=[2x1]{21.3838,-0.8843},time=1225719874.72643280029297,Speed=1.15504804182121,Pitch=0.02916359853990,Roll=0.03140695227374,PitchDot=0.03140695227374,RollDot=-0.00089734149354
-63.079 ODOMETRY_POSE iPlatform Pose=[3x1]{5.2428,19.4810,-0.8837},Vel=[3x1]{-0.8934,-0.7321,-0.6435},Raw=[2x1]{21.3838,-0.8843},time=1225719874.7264,Speed=1.1550,Pitch=-0.0058,Roll=0.0425,PitchDot=0.0257,RollDot=0.0181
-63.070 LMS_LASER_2D_LEFT LMS1 ID=4135,time=1225719874.715445,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=132,Range=[181]{1.026,1.034,1.039,1.046,1.052,1.064,1.076,1.087,1.086,1.098,1.114,1.120,1.132,1.141,1.150,1.168,1.176,1.191,1.198,1.225,1.223,1.251,1.259,1.267,1.283,1.304,1.318,1.335,1.360,1.375,1.392,1.418,1.442,1.464,1.490,1.529,1.556,1.575,1.604,1.635,1.656,1.687,1.708,1.748,1.781,1.804,1.839,1.877,1.900,1.930,1.946,2.023,2.057,2.102,2.172,2.229,2.298,2.347,2.400,2.475,2.543,2.617,2.698,2.700,2.688,2.735,2.865,2.956,3.029,3.094,3.215,3.288,3.366,3.561,3.694,3.832,3.986,4.029,4.016,4.009,4.040,4.074,4.097,4.102,4.096,4.101,4.114,4.098,4.110,4.156,4.182,4.197,4.197,4.216,4.215,4.224,4.224,4.224,4.234,4.233,4.231,4.235,4.234,4.243,4.246,4.255,4.259,4.264,4.267,4.268,4.282,4.292,4.300,4.312,4.314,4.328,4.345,4.356,4.364,4.376,4.385,4.393,4.403,4.410,4.430,4.439,4.448,4.464,2.653,2.846,2.741,2.700,2.613,2.544,2.518,2.471,2.480,2.562,2.601,2.690,4.669,4.688,4.715,4.734,4.758,4.773,4.799,4.827,4.849,4.874,4.902,4.926,4.953,4.970,5.008,5.037,5.069,5.097,5.130,5.165,5.188,5.235,5.256,5.283,5.320,5.357,5.392,5.419,5.454,5.453,5.518,5.514,5.489,5.585,6.025,6.240,6.287,5.576,5.381,5.335,5.414},Reflectance=[181]{44.000,39.000,42.000,45.000,44.000,45.000,43.000,44.000,44.000,46.000,41.000,37.000,42.000,47.000,47.000,43.000,43.000,46.000,41.000,45.000,49.000,41.000,45.000,50.000,49.000,47.000,49.000,52.000,51.000,50.000,54.000,54.000,53.000,51.000,48.000,41.000,37.000,41.000,38.000,41.000,48.000,53.000,46.000,39.000,43.000,46.000,54.000,54.000,57.000,55.000,58.000,54.000,58.000,56.000,48.000,37.000,40.000,43.000,47.000,46.000,52.000,49.000,49.000,50.000,56.000,57.000,52.000,48.000,53.000,51.000,46.000,55.000,55.000,44.000,48.000,51.000,55.000,72.000,69.000,67.000,70.000,72.000,74.000,73.000,71.000,70.000,71.000,72.000,72.000,73.000,74.000,75.000,75.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,31.000,119.000,99.000,94.000,98.000,80.000,79.000,75.000,73.000,74.000,67.000,41.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,77.000,76.000,76.000,75.000,76.000,76.000,76.000,72.000,73.000,69.000,71.000,69.000,69.000,63.000,64.000,64.000,66.000,69.000,68.000,65.000,61.000,73.000,71.000,69.000,80.000,71.000,71.000,75.000}
-63.078 LMS_LASER_2D_RIGHT LMS2 ID=4008,time=1225719874.720983,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=97,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.484,13.657,11.535,10.213,9.299,8.442,7.619,7.000,6.538,6.044,5.663,5.284,4.963,4.681,4.429,4.194,3.967,3.774,3.575,3.422,3.250,3.085,2.947,2.864,2.770,2.644,2.551,2.477,2.407,2.328,2.247,2.192,2.131,2.070,1.991,1.944,1.872,1.824,1.783,1.746,1.716,1.659,1.633,1.597,1.560,1.544,1.509,1.469,1.434,1.414,1.405,1.378,1.357,1.332,1.314,1.287,1.261,1.248,1.235,1.234,1.219,1.216,1.235,1.240,1.234,1.224,1.210,1.197,1.205,1.192,1.179,1.176,1.160,1.153,1.147,1.132,1.115,1.105,1.081,1.055,1.090,1.085,1.072,1.057,1.060,1.031,1.035,0.993,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,95.000,112.000,90.000,72.000,58.000,57.000,56.000,59.000,65.000,68.000,67.000,69.000,70.000,72.000,71.000,74.000,75.000,77.000,76.000,77.000,77.000,77.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,79.000,76.000,63.000,63.000,74.000,77.000,72.000,68.000,72.000,71.000,70.000,72.000,77.000,79.000,78.000,77.000,70.000,61.000,55.000,53.000,56.000,62.000,66.000,59.000,57.000,59.000,57.000,58.000,55.000,42.000,36.000,40.000,42.000,31.000,27.000,36.000,44.000,40.000,38.000,41.000,30.000,35.000,28.000,24.000}
-63.083 LMS_LASER_2D_LEFT LMS1 ID=4136,time=1225719874.728784,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=133,Range=[181]{1.031,1.034,1.041,1.043,1.060,1.058,1.077,1.071,1.090,1.103,1.105,1.124,1.132,1.141,1.147,1.161,1.172,1.191,1.202,1.219,1.232,1.251,1.250,1.267,1.287,1.302,1.317,1.337,1.356,1.375,1.388,1.410,1.439,1.458,1.489,1.518,1.522,1.567,1.603,1.630,1.651,1.689,1.707,1.742,1.761,1.808,1.833,1.863,1.894,1.921,1.982,2.007,2.054,2.098,2.165,2.211,2.279,2.336,2.395,2.460,2.523,2.602,2.686,2.699,2.688,2.718,2.866,2.938,3.029,3.107,3.199,3.273,3.392,3.502,3.645,3.776,3.924,4.014,4.006,4.006,4.034,4.068,4.094,4.095,4.100,4.097,4.111,4.094,4.104,4.141,4.174,4.196,4.188,4.207,4.206,4.217,4.215,4.217,4.226,4.224,4.231,4.227,4.234,4.242,4.244,4.244,4.252,4.265,4.274,4.268,4.275,4.282,4.294,4.301,4.313,4.323,4.332,4.346,4.356,4.367,4.374,4.385,2.546,2.653,2.703,2.558,4.439,2.765,2.687,2.613,2.675,2.750,2.834,2.654,2.494,2.439,2.471,2.619,2.595,2.635,4.665,4.690,4.706,4.725,4.750,4.768,4.790,4.821,4.842,4.866,4.891,4.915,4.944,4.968,5.009,5.029,5.059,5.085,5.120,5.148,5.183,5.219,5.239,5.273,5.300,5.343,5.383,5.411,5.454,5.454,5.499,5.523,5.487,5.533,5.874,6.310,6.359,5.369,5.314,5.295,5.310},Reflectance=[181]{38.000,39.000,43.000,44.000,44.000,43.000,39.000,46.000,45.000,40.000,46.000,42.000,46.000,42.000,46.000,48.000,46.000,45.000,43.000,43.000,41.000,42.000,46.000,46.000,51.000,46.000,49.000,46.000,50.000,50.000,48.000,51.000,52.000,53.000,43.000,35.000,30.000,34.000,34.000,38.000,46.000,45.000,41.000,37.000,33.000,34.000,47.000,52.000,54.000,55.000,55.000,55.000,57.000,50.000,44.000,46.000,39.000,45.000,44.000,47.000,55.000,46.000,47.000,49.000,55.000,57.000,49.000,51.000,50.000,49.000,45.000,52.000,51.000,51.000,45.000,54.000,58.000,70.000,68.000,71.000,71.000,73.000,73.000,73.000,72.000,71.000,70.000,70.000,73.000,71.000,71.000,75.000,75.000,76.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,32.000,117.000,127.000,19.000,79.000,122.000,92.000,75.000,91.000,107.000,108.000,81.000,74.000,71.000,70.000,75.000,68.000,49.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,77.000,77.000,77.000,77.000,78.000,77.000,76.000,76.000,75.000,75.000,75.000,76.000,73.000,71.000,69.000,69.000,66.000,68.000,64.000,67.000,64.000,66.000,69.000,71.000,68.000,62.000,78.000,68.000,65.000,75.000,72.000,72.000,74.000}
-63.095 DESIRED_THRUST iJoystick 84.5393230995
-63.095 DESIRED_RUDDER iJoystick 3.09152500992
-63.119 DESIRED_THRUST iJoystick 84.5393230995
-63.119 DESIRED_RUDDER iJoystick 3.09152500992
-63.090 LMS_LASER_2D_RIGHT LMS2 ID=4009,time=1225719874.734323,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=98,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.208,16.915,13.886,11.786,10.379,9.427,8.559,7.710,7.057,6.597,6.080,5.689,5.336,5.016,4.724,4.473,4.239,3.993,3.792,3.595,3.453,3.269,3.130,2.949,2.869,2.787,2.655,2.568,2.474,2.395,2.330,2.256,2.194,2.131,2.079,1.999,1.944,1.882,1.832,1.770,1.746,1.723,1.669,1.634,1.598,1.555,1.545,1.521,1.478,1.443,1.422,1.417,1.385,1.365,1.331,1.307,1.289,1.263,1.249,1.242,1.234,1.230,1.225,1.230,1.232,1.229,1.212,1.205,1.205,1.201,1.193,1.190,1.164,1.169,1.161,1.149,1.130,1.107,1.104,1.088,1.082,1.090,1.087,1.069,1.070,1.052,1.040,1.035,1.020,1.012},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,78.000,119.000,92.000,75.000,59.000,57.000,57.000,59.000,64.000,68.000,67.000,69.000,69.000,72.000,71.000,73.000,75.000,77.000,77.000,78.000,78.000,77.000,80.000,79.000,80.000,81.000,80.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,79.000,80.000,80.000,80.000,77.000,78.000,80.000,78.000,79.000,79.000,80.000,79.000,77.000,65.000,64.000,76.000,77.000,71.000,67.000,70.000,74.000,73.000,74.000,75.000,78.000,78.000,77.000,71.000,63.000,60.000,58.000,63.000,65.000,64.000,61.000,54.000,56.000,60.000,54.000,55.000,46.000,37.000,40.000,45.000,31.000,30.000,36.000,40.000,39.000,40.000,39.000,36.000,37.000,34.000,32.000}
-63.096 LMS_LASER_2D_LEFT LMS1 ID=4137,time=1225719874.742122,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=134,Range=[181]{1.018,1.032,1.042,1.049,1.050,1.071,1.066,1.075,1.082,1.093,1.098,1.116,1.132,1.135,1.151,1.155,1.170,1.187,1.194,1.216,1.228,1.241,1.252,1.274,1.282,1.300,1.316,1.331,1.350,1.371,1.390,1.412,1.433,1.455,1.484,1.525,1.543,1.582,1.601,1.621,1.651,1.679,1.713,1.738,1.768,1.804,1.832,1.863,1.901,1.937,1.965,2.003,2.049,2.105,2.169,2.219,2.275,2.323,2.386,2.448,2.513,2.586,2.666,2.694,2.677,2.716,2.859,2.932,2.965,3.099,3.181,3.247,3.351,3.491,3.620,3.753,3.914,3.999,4.007,4.007,4.021,4.059,4.081,4.089,4.087,4.089,4.108,4.097,4.102,4.134,4.169,4.187,4.180,4.202,4.217,4.203,4.207,4.208,4.217,4.217,4.217,4.229,4.237,4.233,4.243,4.244,4.244,4.248,4.263,4.267,4.275,4.276,4.291,4.300,4.306,4.313,4.323,4.339,4.346,4.358,2.497,2.629,2.648,2.629,2.532,2.660,2.784,2.777,2.683,2.581,2.587,2.677,2.763,2.571,2.493,2.433,2.495,2.616,2.613,2.744,4.669,4.682,4.698,4.716,4.741,4.766,4.782,4.810,4.833,4.855,4.882,4.909,4.935,4.965,5.000,5.022,5.052,5.077,5.108,5.134,5.165,5.203,5.238,5.256,5.301,5.339,5.373,5.411,5.436,5.454,5.490,5.519,5.490,5.507,5.805,6.341,6.402,5.369,5.250,5.311,3.599},Reflectance=[181]{36.000,42.000,39.000,42.000,43.000,40.000,42.000,43.000,42.000,48.000,45.000,41.000,41.000,43.000,43.000,46.000,44.000,44.000,43.000,41.000,38.000,45.000,47.000,44.000,44.000,49.000,52.000,51.000,51.000,49.000,49.000,51.000,50.000,48.000,44.000,39.000,39.000,37.000,38.000,34.000,39.000,40.000,44.000,44.000,41.000,38.000,38.000,52.000,53.000,54.000,55.000,56.000,55.000,53.000,42.000,37.000,41.000,44.000,44.000,45.000,47.000,47.000,54.000,50.000,55.000,56.000,50.000,56.000,55.000,50.000,46.000,56.000,52.000,58.000,47.000,44.000,54.000,69.000,66.000,65.000,70.000,73.000,74.000,74.000,71.000,72.000,72.000,71.000,73.000,72.000,72.000,75.000,75.000,74.000,76.000,77.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,79.000,79.000,77.000,79.000,78.000,78.000,78.000,77.000,77.000,79.000,78.000,79.000,78.000,78.000,78.000,39.000,119.000,124.000,111.000,75.000,115.000,126.000,127.000,111.000,76.000,76.000,88.000,84.000,80.000,74.000,72.000,72.000,71.000,70.000,102.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,77.000,77.000,76.000,76.000,77.000,75.000,75.000,74.000,74.000,71.000,72.000,71.000,69.000,66.000,67.000,65.000,69.000,66.000,66.000,69.000,70.000,67.000,62.000,76.000,64.000,63.000,83.000,67.000,74.000,110.000}
-63.102 LMS_LASER_2D_RIGHT LMS2 ID=4010,time=1225719874.747662,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=99,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.700,17.355,14.349,12.114,10.551,9.518,8.654,7.766,7.135,6.669,6.181,5.776,5.389,5.050,4.766,4.490,4.265,4.022,3.826,3.646,3.459,3.308,3.140,2.969,2.885,2.798,2.670,2.568,2.491,2.393,2.335,2.257,2.201,2.142,2.087,2.008,1.951,1.892,1.848,1.791,1.749,1.717,1.669,1.642,1.598,1.545,1.545,1.532,1.481,1.447,1.435,1.425,1.394,1.374,1.339,1.313,1.289,1.265,1.253,1.241,1.235,1.230,1.218,1.222,1.237,1.236,1.213,1.198,1.191,1.190,1.195,1.183,1.162,1.170,1.169,1.154,1.131,1.112,1.110,1.096,1.076,1.086,1.082,1.076,1.064,1.061,1.052,1.038,1.030,1.020},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,42.000,67.000,118.000,97.000,78.000,61.000,57.000,58.000,58.000,64.000,67.000,66.000,69.000,69.000,72.000,71.000,73.000,75.000,76.000,77.000,77.000,78.000,77.000,78.000,79.000,81.000,80.000,80.000,79.000,76.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,78.000,79.000,80.000,78.000,79.000,79.000,79.000,79.000,78.000,70.000,70.000,77.000,77.000,69.000,64.000,68.000,70.000,72.000,75.000,74.000,78.000,79.000,77.000,73.000,66.000,62.000,58.000,66.000,69.000,69.000,67.000,58.000,57.000,63.000,59.000,51.000,48.000,40.000,40.000,44.000,34.000,30.000,35.000,38.000,39.000,40.000,39.000,37.000,45.000,49.000,52.000}
-63.110 LMS_LASER_2D_LEFT LMS1 ID=4138,time=1225719874.755461,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=135,Range=[181]{1.030,1.032,1.037,1.047,1.054,1.058,1.073,1.075,1.094,1.085,1.109,1.115,1.124,1.134,1.149,1.163,1.170,1.177,1.195,1.207,1.218,1.241,1.252,1.263,1.286,1.300,1.319,1.329,1.349,1.365,1.385,1.407,1.430,1.459,1.477,1.506,1.538,1.570,1.595,1.632,1.654,1.672,1.711,1.741,1.766,1.794,1.819,1.859,1.877,1.921,1.956,1.994,2.034,2.087,2.145,2.205,2.258,2.323,2.364,2.434,2.502,2.584,2.634,2.648,2.680,2.716,2.825,2.911,2.963,3.075,3.164,3.248,3.282,3.482,3.598,3.715,3.890,3.963,3.994,3.999,4.014,4.049,4.077,4.086,4.089,4.091,4.097,4.098,4.091,4.125,4.158,4.184,4.181,4.196,4.211,4.206,4.206,4.208,4.209,4.215,4.217,4.226,4.226,4.234,4.234,4.242,4.242,4.243,4.252,4.260,4.267,4.273,4.280,4.291,4.294,4.306,4.314,4.332,4.346,2.474,2.535,2.463,2.486,2.505,2.519,2.533,2.553,2.567,2.604,2.682,2.696,2.755,2.732,2.518,2.531,2.469,2.601,2.654,2.741,2.781,2.681,4.672,4.691,4.716,4.734,4.759,4.766,4.800,4.817,4.849,4.883,4.899,4.925,4.947,4.988,5.013,5.043,5.068,5.089,5.134,5.149,5.194,5.224,5.250,5.283,5.324,5.355,5.398,5.431,5.463,5.463,5.513,5.498,5.498,5.729,6.384,5.204,5.403,5.213,5.321,3.504},Reflectance=[181]{41.000,38.000,41.000,45.000,46.000,43.000,45.000,43.000,39.000,39.000,43.000,45.000,45.000,43.000,42.000,40.000,48.000,43.000,44.000,45.000,47.000,45.000,42.000,43.000,45.000,49.000,46.000,54.000,51.000,50.000,51.000,53.000,52.000,49.000,35.000,32.000,41.000,44.000,43.000,39.000,41.000,41.000,38.000,40.000,39.000,36.000,44.000,45.000,54.000,55.000,55.000,56.000,56.000,52.000,39.000,38.000,42.000,49.000,48.000,47.000,50.000,46.000,60.000,58.000,52.000,56.000,50.000,47.000,48.000,51.000,51.000,57.000,60.000,50.000,49.000,46.000,51.000,66.000,67.000,65.000,70.000,73.000,73.000,73.000,72.000,72.000,71.000,72.000,72.000,72.000,71.000,74.000,76.000,75.000,77.000,78.000,78.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,79.000,78.000,79.000,78.000,77.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,26.000,99.000,75.000,75.000,75.000,74.000,76.000,76.000,75.000,80.000,94.000,107.000,27.000,107.000,71.000,67.000,75.000,72.000,84.000,89.000,101.000,22.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,75.000,77.000,75.000,75.000,74.000,74.000,69.000,72.000,72.000,70.000,66.000,68.000,64.000,68.000,67.000,64.000,66.000,70.000,65.000,62.000,65.000,62.000,19.000,88.000,67.000,72.000,100.000}
-63.114 LMS_LASER_2D_RIGHT LMS2 ID=4011,time=1225719874.761000,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=100,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.743,17.581,14.499,12.205,10.665,9.617,8.763,7.917,7.198,6.705,6.217,5.785,5.441,5.093,4.775,4.509,4.293,4.040,3.842,3.665,3.468,3.305,3.152,2.988,2.895,2.804,2.689,2.575,2.502,2.406,2.347,2.266,2.194,2.142,2.087,2.017,1.969,1.899,1.858,1.799,1.750,1.725,1.668,1.633,1.572,1.538,1.539,1.526,1.483,1.449,1.437,1.422,1.387,1.377,1.322,1.304,1.296,1.273,1.254,1.254,1.233,1.222,1.218,1.215,1.231,1.231,1.231,1.226,1.205,1.196,1.191,1.182,1.181,1.177,1.174,1.169,1.137,1.108,1.110,1.104,1.095,1.067,1.081,1.074,1.067,1.053,1.049,1.037,1.017,1.014},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,44.000,62.000,119.000,98.000,80.000,61.000,57.000,57.000,59.000,63.000,67.000,66.000,68.000,69.000,72.000,72.000,73.000,75.000,76.000,77.000,77.000,78.000,77.000,79.000,79.000,80.000,81.000,80.000,80.000,75.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,78.000,80.000,80.000,76.000,76.000,77.000,77.000,80.000,79.000,74.000,73.000,76.000,76.000,74.000,70.000,69.000,70.000,72.000,74.000,77.000,79.000,78.000,77.000,72.000,69.000,64.000,60.000,55.000,57.000,64.000,65.000,61.000,60.000,56.000,54.000,49.000,44.000,40.000,38.000,43.000,39.000,33.000,30.000,38.000,43.000,43.000,40.000,41.000,52.000,54.000,53.000}
-63.115 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.2788,19.5103,-0.8917},Vel=[3x1]{-0.9215,-0.7438,10.6410},Raw=[2x1]{21.4303,-0.8917},time=1225719874.76239395141602,Speed=1.18425279635525,Pitch=0.03140695227374,Roll=0.02692024480606,PitchDot=0.05608384334597,RollDot=-0.00105437625490
-63.115 ODOMETRY_POSE iPlatform Pose=[3x1]{5.2788,19.5103,-0.8913},Vel=[3x1]{-0.9215,-0.7438,-1.9249},Raw=[2x1]{21.4303,-0.8917},time=1225719874.7624,Speed=1.1843,Pitch=-0.0012,Roll=0.0413,PitchDot=-0.0185,RollDot=0.0530
-63.143 DESIRED_THRUST iJoystick 84.5393230995
-63.143 DESIRED_RUDDER iJoystick 3.09152500992
-62.283 CAMERA_FILE_WRITE iCameraLadybug time=1225719873.931,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.931-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.931-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.931-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.931-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719873.931-4.jpg
-63.074 ICAMERALADYBUG_STATUS iCameraLadybug AppErrorFlag=false,Uptime=-1615.49,MOOSName=iCameraLadybug,Publishing=CAMERA_FILE_WRITE,ICAMERALADYBUG_STATUS,Subscribing=CAMERA_COMMAND,LOGGER_DIRECTORY,MARGE_ODOMETRY,NAV_POSE,SET_INTERPOSE_COMMAND,
-63.122 LMS_LASER_2D_LEFT LMS1 ID=4139,time=1225719874.768798,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=136,Range=[181]{1.023,1.031,1.042,1.043,1.051,1.056,1.067,1.073,1.090,1.092,1.105,1.112,1.124,1.132,1.149,1.161,1.166,1.186,1.191,1.206,1.216,1.233,1.255,1.259,1.277,1.291,1.313,1.329,1.350,1.366,1.386,1.408,1.425,1.456,1.462,1.492,1.548,1.557,1.581,1.627,1.647,1.674,1.704,1.723,1.743,1.792,1.821,1.856,1.890,1.915,1.956,1.998,2.050,2.098,2.150,2.198,2.251,2.298,2.331,2.434,2.503,2.567,2.641,2.668,2.687,2.724,2.821,2.903,2.971,3.048,3.156,3.236,3.292,3.421,3.572,3.706,3.859,3.952,3.994,3.999,4.008,4.050,4.075,4.082,4.089,4.079,4.100,4.098,4.087,4.109,4.149,4.181,4.181,4.185,4.210,4.203,4.206,4.207,4.206,4.208,4.215,4.226,4.226,4.226,4.232,4.233,4.242,4.243,4.251,4.253,4.260,4.265,4.280,4.283,4.293,4.306,4.314,4.323,4.337,4.346,2.593,2.465,2.472,2.488,2.526,2.601,2.579,2.561,2.578,2.640,2.795,2.630,2.648,2.566,2.591,2.567,2.622,2.690,2.664,2.751,2.693,4.664,4.691,4.708,4.732,4.751,4.774,4.797,4.815,4.849,4.874,4.899,4.916,4.946,4.989,5.013,5.043,5.061,5.086,5.119,5.145,5.178,5.217,5.242,5.279,5.319,5.349,5.384,5.420,5.454,5.472,5.523,5.497,5.489,5.671,5.463,5.278,5.306,5.193,3.522,3.380},Reflectance=[181]{42.000,42.000,43.000,39.000,43.000,42.000,43.000,45.000,41.000,43.000,41.000,44.000,42.000,42.000,42.000,43.000,46.000,39.000,46.000,46.000,46.000,46.000,44.000,46.000,46.000,49.000,47.000,50.000,51.000,50.000,51.000,50.000,50.000,39.000,30.000,30.000,46.000,42.000,32.000,41.000,43.000,38.000,39.000,53.000,47.000,36.000,35.000,37.000,52.000,56.000,59.000,54.000,48.000,45.000,45.000,43.000,43.000,52.000,56.000,42.000,47.000,55.000,55.000,55.000,51.000,56.000,48.000,47.000,47.000,47.000,47.000,48.000,61.000,51.000,46.000,46.000,49.000,68.000,67.000,64.000,69.000,73.000,75.000,75.000,72.000,71.000,72.000,72.000,71.000,70.000,71.000,73.000,76.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,77.000,77.000,78.000,78.000,78.000,79.000,79.000,77.000,78.000,121.000,78.000,75.000,75.000,80.000,95.000,82.000,76.000,76.000,83.000,113.000,38.000,96.000,72.000,74.000,75.000,75.000,76.000,74.000,92.000,39.000,79.000,79.000,79.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,76.000,75.000,77.000,75.000,73.000,73.000,72.000,70.000,70.000,73.000,70.000,68.000,69.000,67.000,67.000,69.000,65.000,64.000,73.000,66.000,63.000,63.000,93.000,78.000,75.000,69.000,101.000,76.000}
-63.126 LMS_LASER_2D_RIGHT LMS2 ID=4012,time=1225719874.774336,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=101,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.939,18.246,14.973,12.481,10.770,9.693,8.827,7.989,7.288,6.768,6.306,5.850,5.459,5.103,4.818,4.510,4.314,4.052,3.867,3.676,3.485,3.333,3.166,3.044,2.914,2.806,2.697,2.587,2.513,2.423,2.355,2.274,2.202,2.143,2.086,2.037,1.969,1.910,1.864,1.801,1.759,1.725,1.653,1.630,1.544,1.527,1.529,1.521,1.492,1.459,1.440,1.420,1.389,1.369,1.322,1.305,1.290,1.279,1.262,1.251,1.235,1.231,1.214,1.215,1.235,1.233,1.238,1.241,1.229,1.200,1.186,1.186,1.182,1.165,1.161,1.168,1.137,1.115,1.110,1.103,1.096,1.069,1.073,1.069,1.064,1.062,1.053,1.033,1.025,1.021},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,38.000,34.000,123.000,98.000,82.000,63.000,57.000,57.000,57.000,63.000,67.000,66.000,69.000,70.000,71.000,72.000,74.000,75.000,76.000,78.000,77.000,78.000,78.000,80.000,77.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,81.000,79.000,80.000,80.000,80.000,80.000,80.000,78.000,79.000,80.000,74.000,66.000,71.000,77.000,77.000,77.000,77.000,74.000,77.000,76.000,74.000,73.000,70.000,72.000,74.000,76.000,77.000,78.000,79.000,78.000,75.000,68.000,61.000,56.000,54.000,56.000,54.000,61.000,62.000,62.000,60.000,60.000,58.000,41.000,37.000,38.000,41.000,37.000,35.000,31.000,32.000,35.000,46.000,45.000,44.000,54.000,54.000,49.000}
-63.134 LMS_LASER_2D_LEFT LMS1 ID=4140,time=1225719874.782134,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=137,Range=[181]{1.022,1.029,1.029,1.039,1.052,1.054,1.061,1.073,1.081,1.094,1.105,1.116,1.125,1.135,1.139,1.163,1.167,1.182,1.202,1.195,1.212,1.218,1.240,1.262,1.273,1.290,1.314,1.336,1.348,1.369,1.387,1.400,1.423,1.451,1.456,1.492,1.540,1.556,1.598,1.619,1.644,1.664,1.690,1.712,1.742,1.783,1.818,1.856,1.890,1.902,1.954,1.991,2.047,2.097,2.140,2.183,2.243,2.291,2.328,2.404,2.497,2.563,2.631,2.669,2.681,2.704,2.799,2.882,2.970,3.043,3.123,3.216,3.323,3.441,3.569,3.699,3.828,3.956,3.984,3.990,4.001,4.044,4.064,4.084,4.081,4.075,4.082,4.093,4.077,4.100,4.141,4.174,4.180,4.177,4.208,4.203,4.197,4.199,4.208,4.207,4.217,4.226,4.216,4.217,4.226,4.234,4.237,4.244,4.243,4.252,4.253,4.267,4.276,4.286,4.294,4.304,4.313,4.323,4.337,4.344,4.355,2.593,2.540,2.515,2.568,2.653,2.628,2.646,2.627,2.690,2.740,2.579,2.528,2.556,2.576,2.637,2.652,2.650,2.739,2.790,2.695,4.664,4.680,4.698,4.723,4.750,4.764,4.780,4.816,4.843,4.867,4.893,4.917,4.950,4.973,5.012,5.034,5.048,5.081,5.105,5.146,5.171,5.207,5.238,5.272,5.310,5.336,5.374,5.413,5.445,5.466,5.513,5.502,5.472,5.604,5.417,5.256,3.380,3.524,3.370,3.366},Reflectance=[181]{42.000,40.000,40.000,42.000,36.000,35.000,40.000,42.000,41.000,44.000,41.000,41.000,42.000,43.000,46.000,44.000,42.000,46.000,43.000,44.000,48.000,51.000,46.000,48.000,49.000,48.000,51.000,49.000,50.000,48.000,51.000,50.000,49.000,35.000,29.000,31.000,42.000,50.000,40.000,35.000,45.000,42.000,45.000,52.000,46.000,39.000,39.000,37.000,44.000,54.000,54.000,55.000,45.000,41.000,38.000,46.000,43.000,53.000,55.000,49.000,43.000,53.000,59.000,55.000,52.000,55.000,54.000,49.000,47.000,48.000,49.000,47.000,48.000,49.000,48.000,50.000,53.000,64.000,67.000,65.000,69.000,74.000,75.000,75.000,72.000,70.000,70.000,70.000,68.000,70.000,71.000,73.000,75.000,75.000,76.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,122.000,95.000,83.000,97.000,117.000,94.000,94.000,82.000,93.000,98.000,82.000,72.000,72.000,75.000,77.000,76.000,75.000,85.000,93.000,20.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,77.000,76.000,77.000,75.000,72.000,72.000,71.000,70.000,70.000,72.000,69.000,68.000,69.000,69.000,67.000,70.000,66.000,58.000,70.000,67.000,66.000,64.000,80.000,74.000,21.000,110.000,76.000,77.000}
-63.138 LMS_LASER_2D_RIGHT LMS2 ID=4013,time=1225719874.787671,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=102,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.229,18.223,15.098,12.576,10.868,9.767,8.900,8.078,7.335,6.794,6.357,5.877,5.485,5.138,4.838,4.519,4.340,4.077,3.881,3.673,3.502,3.325,3.166,3.051,2.919,2.821,2.698,2.605,2.515,2.434,2.356,2.271,2.194,2.118,2.092,2.036,1.970,1.898,1.858,1.806,1.749,1.725,1.667,1.623,1.553,1.519,1.510,1.520,1.497,1.466,1.442,1.428,1.387,1.351,1.306,1.297,1.289,1.270,1.253,1.240,1.233,1.224,1.219,1.216,1.230,1.243,1.240,1.240,1.226,1.200,1.187,1.179,1.173,1.154,1.161,1.156,1.140,1.125,1.097,1.105,1.094,1.067,1.056,1.074,1.067,1.066,1.045,1.024,1.032,1.025},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,48.000,21.000,123.000,101.000,83.000,64.000,57.000,57.000,55.000,63.000,66.000,67.000,68.000,69.000,71.000,73.000,74.000,75.000,75.000,77.000,77.000,78.000,78.000,80.000,79.000,80.000,81.000,80.000,81.000,81.000,81.000,80.000,78.000,73.000,79.000,80.000,80.000,79.000,80.000,80.000,79.000,79.000,78.000,69.000,72.000,77.000,74.000,74.000,75.000,73.000,77.000,75.000,73.000,74.000,74.000,73.000,72.000,72.000,73.000,78.000,78.000,78.000,77.000,69.000,59.000,53.000,51.000,59.000,57.000,57.000,63.000,64.000,60.000,65.000,62.000,48.000,36.000,38.000,40.000,42.000,35.000,30.000,29.000,38.000,41.000,43.000,48.000,58.000,53.000,43.000}
-63.147 LMS_LASER_2D_LEFT LMS1 ID=4141,time=1225719874.795471,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=138,Range=[181]{1.025,1.029,1.039,1.044,1.051,1.054,1.071,1.076,1.086,1.094,1.103,1.101,1.124,1.136,1.149,1.151,1.171,1.176,1.193,1.208,1.216,1.226,1.240,1.257,1.269,1.291,1.312,1.328,1.346,1.369,1.383,1.398,1.424,1.453,1.489,1.512,1.536,1.572,1.597,1.619,1.639,1.668,1.702,1.725,1.751,1.782,1.810,1.840,1.882,1.912,1.952,1.989,2.048,2.092,2.125,2.180,2.247,2.301,2.328,2.411,2.482,2.562,2.619,2.673,2.668,2.691,2.805,2.875,2.964,3.026,3.121,3.201,3.293,3.419,3.562,3.703,3.855,3.964,3.990,3.999,3.997,4.041,4.063,4.075,4.081,4.072,4.079,4.087,4.079,4.097,4.138,4.171,4.174,4.173,4.199,4.202,4.197,4.199,4.198,4.208,4.208,4.215,4.217,4.217,4.217,4.231,4.229,4.234,4.246,4.246,4.258,4.261,4.272,4.272,4.281,4.296,4.306,4.321,4.329,4.338,4.349,4.358,2.591,2.585,2.457,2.581,2.640,2.645,2.674,2.688,2.690,2.600,2.543,2.569,2.733,2.763,2.685,2.677,2.763,2.713,4.641,4.654,4.672,4.698,4.716,4.740,4.757,4.779,4.814,4.832,4.857,4.883,4.915,4.942,4.963,5.000,5.033,5.040,5.077,5.108,5.131,5.171,5.203,5.232,5.264,5.309,5.332,5.373,5.410,5.445,5.469,5.506,5.506,5.473,5.576,3.365,3.354,3.430,3.336,3.337,3.348},Reflectance=[181]{39.000,41.000,42.000,37.000,39.000,40.000,41.000,39.000,44.000,44.000,44.000,48.000,45.000,44.000,42.000,43.000,44.000,43.000,43.000,45.000,46.000,51.000,50.000,46.000,47.000,44.000,46.000,50.000,46.000,48.000,54.000,52.000,49.000,35.000,36.000,35.000,33.000,40.000,39.000,34.000,48.000,44.000,38.000,40.000,45.000,38.000,36.000,41.000,41.000,51.000,50.000,47.000,42.000,43.000,47.000,48.000,41.000,45.000,55.000,48.000,44.000,44.000,58.000,53.000,55.000,57.000,52.000,46.000,48.000,48.000,48.000,47.000,46.000,47.000,53.000,48.000,54.000,64.000,69.000,62.000,68.000,73.000,74.000,75.000,72.000,69.000,69.000,69.000,66.000,69.000,70.000,72.000,76.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,29.000,112.000,76.000,108.000,113.000,93.000,95.000,92.000,93.000,94.000,73.000,73.000,92.000,93.000,77.000,78.000,93.000,34.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,75.000,76.000,75.000,70.000,70.000,69.000,69.000,70.000,72.000,70.000,69.000,69.000,67.000,65.000,69.000,65.000,59.000,69.000,69.000,67.000,65.000,22.000,46.000,96.000,76.000,76.000,77.000}
-63.151 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.3062,19.5323,-0.8965},Vel=[3x1]{-0.9228,-0.7376,8.5897},Raw=[2x1]{21.4654,-0.8965},time=1225719874.79844498634338,Speed=1.18133232090184,Pitch=0.03140695227374,Roll=0.02467689107222,PitchDot=0.03589365974142,RollDot=-0.00033650306008
-63.151 ODOMETRY_POSE iPlatform Pose=[3x1]{5.3062,19.5323,-0.8961},Vel=[3x1]{-0.9228,-0.7376,2.3062},Raw=[2x1]{21.4654,-0.8965},time=1225719874.7984,Speed=1.1813,Pitch=0.0003,Roll=0.0399,PitchDot=-0.0243,RollDot=-0.0264
-63.167 DESIRED_THRUST iJoystick 84.5393230995
-63.167 DESIRED_RUDDER iJoystick 2.05999938963
-63.150 LMS_LASER_2D_RIGHT LMS2 ID=4014,time=1225719874.801004,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=103,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.150,18.297,15.101,12.610,10.895,9.775,8.908,8.070,7.345,6.818,6.374,5.877,5.485,5.164,4.847,4.519,4.343,4.086,3.891,3.698,3.505,3.334,3.178,3.071,2.929,2.812,2.669,2.604,2.514,2.424,2.364,2.274,2.192,2.140,2.101,2.041,1.983,1.907,1.858,1.788,1.748,1.732,1.698,1.645,1.609,1.554,1.526,1.511,1.483,1.473,1.446,1.423,1.377,1.342,1.323,1.308,1.297,1.261,1.250,1.243,1.232,1.224,1.219,1.209,1.234,1.244,1.245,1.247,1.223,1.212,1.181,1.180,1.171,1.155,1.162,1.151,1.143,1.123,1.106,1.098,1.099,1.055,1.051,1.079,1.071,1.058,1.050,1.035,1.029,1.026},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,51.000,17.000,129.000,100.000,83.000,64.000,57.000,57.000,56.000,62.000,65.000,67.000,69.000,69.000,71.000,74.000,75.000,75.000,75.000,77.000,78.000,78.000,79.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,78.000,78.000,80.000,79.000,80.000,79.000,80.000,80.000,79.000,79.000,79.000,77.000,74.000,74.000,72.000,74.000,73.000,70.000,75.000,74.000,71.000,72.000,76.000,74.000,73.000,72.000,75.000,78.000,78.000,78.000,76.000,72.000,61.000,53.000,50.000,51.000,60.000,63.000,69.000,66.000,65.000,66.000,63.000,54.000,47.000,40.000,40.000,46.000,50.000,27.000,26.000,35.000,40.000,43.000,43.000,51.000,49.000,44.000}
-63.158 LMS_LASER_2D_LEFT LMS1 ID=4142,time=1225719874.808804,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=139,Range=[181]{1.020,1.034,1.040,1.048,1.057,1.066,1.060,1.073,1.084,1.090,1.103,1.110,1.126,1.133,1.147,1.157,1.164,1.178,1.191,1.208,1.218,1.235,1.243,1.257,1.272,1.291,1.309,1.325,1.344,1.365,1.379,1.405,1.424,1.457,1.476,1.523,1.541,1.574,1.598,1.617,1.651,1.667,1.688,1.718,1.747,1.763,1.810,1.845,1.879,1.925,1.957,2.007,2.040,2.088,2.139,2.164,2.243,2.290,2.339,2.419,2.486,2.546,2.622,2.680,2.668,2.688,2.802,2.868,2.949,3.020,3.104,3.206,3.292,3.411,3.532,3.693,3.861,3.973,3.989,3.990,3.997,4.031,4.063,4.072,4.082,4.076,4.078,4.088,4.069,4.097,4.130,4.171,4.173,4.173,4.197,4.193,4.190,4.199,4.199,4.199,4.209,4.208,4.208,4.217,4.218,4.226,4.229,4.234,4.234,4.246,4.255,4.261,4.270,4.278,4.283,4.287,4.295,4.313,4.328,4.338,4.349,2.622,2.605,2.397,2.413,2.482,2.443,2.565,2.631,2.732,2.720,2.712,2.700,2.617,2.745,2.800,2.731,2.771,2.925,2.734,4.634,4.653,4.672,4.698,4.715,4.734,4.758,4.780,4.806,4.833,4.857,4.882,4.907,4.933,4.957,4.998,5.021,5.040,5.071,5.098,5.136,5.165,5.194,5.221,5.267,5.298,5.331,5.365,5.407,5.445,5.473,5.506,5.504,5.472,3.328,3.310,3.340,3.322,3.322,3.332,3.331},Reflectance=[181]{41.000,39.000,38.000,41.000,38.000,42.000,44.000,45.000,43.000,42.000,40.000,43.000,43.000,42.000,41.000,45.000,46.000,39.000,46.000,45.000,47.000,47.000,47.000,46.000,48.000,49.000,52.000,48.000,49.000,50.000,52.000,52.000,46.000,36.000,32.000,38.000,36.000,37.000,40.000,45.000,39.000,39.000,33.000,41.000,38.000,32.000,34.000,36.000,39.000,40.000,43.000,38.000,42.000,41.000,41.000,49.000,43.000,40.000,48.000,39.000,45.000,46.000,51.000,52.000,55.000,56.000,48.000,46.000,49.000,49.000,48.000,46.000,45.000,51.000,48.000,51.000,53.000,62.000,69.000,63.000,68.000,73.000,74.000,74.000,72.000,70.000,69.000,69.000,66.000,69.000,70.000,72.000,75.000,75.000,75.000,77.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,78.000,79.000,21.000,115.000,74.000,71.000,83.000,75.000,87.000,88.000,107.000,33.000,97.000,87.000,74.000,93.000,83.000,75.000,86.000,111.000,17.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,74.000,72.000,71.000,69.000,72.000,71.000,72.000,69.000,69.000,68.000,67.000,64.000,68.000,65.000,57.000,69.000,68.000,64.000,31.000,66.000,81.000,77.000,77.000,78.000,77.000}
-63.167 LMS_LASER_2D_RIGHT LMS2 ID=4015,time=1225719874.814341,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=104,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.097,18.313,15.056,12.637,10.907,9.784,8.917,8.077,7.370,6.819,6.366,5.885,5.494,5.183,4.856,4.545,4.363,4.096,3.885,3.690,3.490,3.329,3.165,3.062,2.932,2.813,2.644,2.587,2.505,2.434,2.374,2.284,2.215,2.156,2.104,2.042,1.969,1.895,1.856,1.803,1.767,1.735,1.697,1.660,1.632,1.583,1.566,1.542,1.516,1.480,1.439,1.411,1.382,1.351,1.329,1.307,1.288,1.262,1.254,1.238,1.232,1.223,1.219,1.216,1.228,1.235,1.241,1.240,1.229,1.209,1.189,1.180,1.179,1.162,1.158,1.147,1.154,1.116,1.105,1.105,1.088,1.064,1.049,1.075,1.073,1.062,1.051,1.043,1.037,1.029},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,31.000,15.000,131.000,100.000,84.000,64.000,57.000,57.000,55.000,63.000,65.000,67.000,67.000,69.000,71.000,73.000,75.000,75.000,77.000,77.000,78.000,80.000,78.000,80.000,80.000,80.000,81.000,80.000,80.000,81.000,81.000,80.000,79.000,80.000,80.000,80.000,80.000,78.000,80.000,79.000,79.000,80.000,79.000,78.000,78.000,75.000,77.000,78.000,71.000,69.000,72.000,75.000,75.000,74.000,75.000,74.000,72.000,73.000,77.000,77.000,78.000,78.000,77.000,70.000,62.000,57.000,52.000,51.000,62.000,61.000,66.000,67.000,64.000,64.000,61.000,56.000,45.000,38.000,42.000,42.000,35.000,29.000,28.000,36.000,42.000,45.000,44.000,41.000,42.000,37.000}
-63.170 LMS_LASER_2D_LEFT LMS1 ID=4143,time=1225719874.822136,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=140,Range=[181]{1.019,1.030,1.032,1.031,1.045,1.056,1.066,1.073,1.086,1.091,1.101,1.116,1.119,1.142,1.149,1.157,1.168,1.189,1.196,1.210,1.219,1.225,1.250,1.268,1.280,1.295,1.309,1.329,1.338,1.364,1.380,1.404,1.423,1.457,1.481,1.516,1.541,1.573,1.593,1.618,1.645,1.671,1.692,1.712,1.750,1.777,1.814,1.839,1.864,1.916,1.957,1.992,2.048,2.092,2.140,2.176,2.242,2.297,2.360,2.417,2.486,2.559,2.639,2.665,2.664,2.688,2.800,2.869,2.949,3.017,3.088,3.218,3.301,3.408,3.508,3.698,3.829,3.973,3.986,3.990,3.994,4.032,4.063,4.076,4.079,4.077,4.077,4.087,4.068,4.094,4.140,4.163,4.174,4.172,4.191,4.189,4.191,4.191,4.199,4.202,4.199,4.208,4.209,4.216,4.220,4.220,4.227,4.229,4.234,4.243,4.250,4.255,4.265,4.279,4.281,4.289,4.298,4.306,4.328,4.340,4.349,4.358,2.657,2.495,2.415,2.437,2.433,2.523,2.614,2.589,2.943,2.853,2.653,2.605,2.700,2.765,2.788,2.899,2.993,4.614,4.637,4.654,4.670,4.691,4.706,4.732,4.757,4.778,4.806,4.833,4.857,4.885,4.908,4.934,4.960,4.992,5.022,5.044,5.071,5.096,5.134,5.165,5.203,5.225,5.259,5.297,5.322,5.365,5.410,5.436,5.469,5.496,3.319,3.316,3.308,3.295,3.297,3.298,3.308,3.318,3.327},Reflectance=[181]{40.000,41.000,42.000,47.000,46.000,45.000,42.000,45.000,40.000,38.000,38.000,42.000,43.000,38.000,42.000,45.000,43.000,40.000,40.000,43.000,48.000,46.000,45.000,45.000,43.000,46.000,44.000,50.000,50.000,53.000,49.000,48.000,49.000,40.000,34.000,39.000,36.000,41.000,42.000,40.000,37.000,40.000,42.000,43.000,36.000,40.000,42.000,50.000,52.000,44.000,43.000,48.000,41.000,38.000,41.000,45.000,43.000,40.000,45.000,43.000,46.000,47.000,46.000,50.000,57.000,56.000,47.000,47.000,49.000,55.000,53.000,48.000,45.000,53.000,50.000,53.000,58.000,63.000,68.000,63.000,67.000,73.000,74.000,75.000,74.000,71.000,68.000,69.000,68.000,70.000,71.000,72.000,76.000,75.000,76.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,78.000,79.000,79.000,124.000,93.000,69.000,75.000,77.000,81.000,86.000,34.000,121.000,90.000,80.000,70.000,83.000,84.000,82.000,104.000,110.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,76.000,75.000,76.000,73.000,71.000,74.000,73.000,72.000,70.000,70.000,68.000,67.000,65.000,69.000,66.000,55.000,68.000,14.000,52.000,76.000,77.000,77.000,78.000,78.000,79.000,79.000}
-63.187 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.3425,19.5612,-0.9018},Vel=[3x1]{-0.9118,-0.7209,7.3077},Raw=[2x1]{21.5118,-0.9018},time=1225719874.83438396453857,Speed=1.16234923045472,Pitch=0.03365030600758,Roll=0.02467689107222,PitchDot=0.03589365974142,RollDot=-0.00008973414935
-63.187 ODOMETRY_POSE iPlatform Pose=[3x1]{5.3425,19.5612,-0.9014},Vel=[3x1]{-0.9118,-0.7209,1.0248},Raw=[2x1]{21.5118,-0.9018},time=1225719874.8344,Speed=1.1623,Pitch=0.0015,Roll=0.0417,PitchDot=0.0186,RollDot=-0.0307
-63.191 DESIRED_THRUST iJoystick 85.5708487197
-63.191 DESIRED_RUDDER iJoystick 1.02847376934
-62.815 RELAYBOX_STATUS iRelayBox LADYBUG is OFF,LMS1 is ON,LMS2 is ON,P10 is OFF,P11 is OFF,P12 is OFF,P13 is OFF,P14 is OFF,P15 is OFF,P16 is OFF,P5 is OFF,P6 is OFF,P7 is OFF,P8 is OFF,P9 is OFF,PANTILT is ON,
-63.182 LMS_LASER_2D_LEFT LMS1 ID=4144,time=1225719874.835468,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=141,Range=[181]{1.018,1.031,1.038,1.043,1.050,1.056,1.069,1.077,1.082,1.090,1.100,1.118,1.124,1.141,1.147,1.158,1.174,1.185,1.191,1.208,1.222,1.237,1.253,1.260,1.277,1.290,1.304,1.327,1.346,1.365,1.389,1.407,1.434,1.468,1.491,1.525,1.547,1.575,1.588,1.623,1.644,1.667,1.690,1.712,1.738,1.777,1.816,1.842,1.864,1.898,1.965,1.999,2.039,2.089,2.124,2.188,2.209,2.275,2.359,2.424,2.483,2.566,2.633,2.675,2.660,2.704,2.808,2.876,2.950,3.017,3.076,3.217,3.303,3.414,3.530,3.684,3.811,3.931,3.973,3.997,3.988,4.033,4.055,4.067,4.077,4.068,4.076,4.092,4.071,4.096,4.133,4.166,4.167,4.173,4.191,4.188,4.190,4.191,4.199,4.200,4.199,4.205,4.211,4.208,4.217,4.218,4.226,4.227,4.243,4.246,4.248,4.266,4.261,4.272,4.279,4.287,4.298,4.306,4.326,4.340,4.350,2.502,2.665,2.579,2.457,2.503,2.497,2.601,2.705,2.708,2.947,2.769,2.622,2.659,2.779,2.798,2.884,2.902,2.727,4.616,4.636,4.652,4.673,4.686,4.715,4.740,4.756,4.777,4.806,4.831,4.858,4.885,4.909,4.934,4.958,4.990,5.016,5.049,5.072,5.101,5.131,5.167,5.198,5.221,5.266,5.298,5.323,5.365,5.411,5.445,5.468,3.284,3.275,3.276,3.272,3.273,3.283,3.292,3.301,3.309,3.327},Reflectance=[181]{44.000,41.000,41.000,44.000,43.000,45.000,44.000,44.000,42.000,42.000,47.000,43.000,42.000,42.000,41.000,42.000,42.000,43.000,45.000,46.000,44.000,48.000,43.000,47.000,45.000,48.000,47.000,49.000,50.000,50.000,49.000,50.000,45.000,41.000,39.000,36.000,37.000,41.000,44.000,38.000,45.000,44.000,45.000,48.000,49.000,41.000,38.000,43.000,52.000,48.000,43.000,47.000,46.000,45.000,32.000,43.000,57.000,45.000,44.000,45.000,44.000,46.000,48.000,54.000,55.000,55.000,46.000,46.000,46.000,56.000,55.000,51.000,46.000,49.000,47.000,55.000,63.000,67.000,65.000,60.000,68.000,74.000,75.000,75.000,73.000,70.000,68.000,70.000,69.000,71.000,71.000,73.000,76.000,75.000,76.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,77.000,78.000,79.000,31.000,124.000,99.000,74.000,83.000,78.000,87.000,107.000,40.000,108.000,85.000,75.000,83.000,89.000,92.000,84.000,114.000,42.000,77.000,78.000,78.000,76.000,77.000,78.000,78.000,78.000,76.000,77.000,77.000,77.000,78.000,77.000,77.000,76.000,76.000,75.000,75.000,74.000,72.000,73.000,71.000,73.000,69.000,69.000,68.000,67.000,65.000,69.000,65.000,59.000,31.000,63.000,76.000,77.000,78.000,78.000,79.000,79.000,78.000,78.000}
-63.190 LMS_LASER_2D_RIGHT LMS2 ID=4016,time=1225719874.827688,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=105,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.264,18.280,14.977,12.566,10.869,9.775,8.891,8.086,7.333,6.801,6.331,5.850,5.485,5.183,4.838,4.588,4.332,4.068,3.867,3.681,3.500,3.305,3.166,3.062,2.923,2.790,2.628,2.553,2.506,2.425,2.362,2.291,2.215,2.147,2.101,2.036,1.958,1.905,1.863,1.813,1.759,1.724,1.693,1.663,1.633,1.580,1.561,1.541,1.513,1.488,1.455,1.423,1.401,1.360,1.324,1.297,1.289,1.253,1.253,1.236,1.223,1.222,1.212,1.215,1.234,1.229,1.238,1.231,1.222,1.198,1.190,1.187,1.182,1.167,1.159,1.140,1.140,1.117,1.109,1.100,1.088,1.091,1.079,1.073,1.058,1.059,1.053,1.040,1.036,1.028},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,47.000,22.000,130.000,101.000,83.000,64.000,57.000,57.000,54.000,62.000,66.000,66.000,69.000,69.000,72.000,71.000,74.000,75.000,76.000,76.000,79.000,78.000,78.000,80.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,78.000,79.000,80.000,79.000,77.000,78.000,80.000,78.000,77.000,78.000,78.000,75.000,66.000,69.000,76.000,75.000,73.000,73.000,72.000,73.000,73.000,76.000,77.000,78.000,77.000,74.000,67.000,61.000,58.000,50.000,60.000,65.000,68.000,68.000,63.000,60.000,61.000,58.000,57.000,52.000,41.000,43.000,43.000,32.000,36.000,35.000,34.000,36.000,43.000,45.000,38.000,39.000,37.000}
-63.215 DESIRED_THRUST iJoystick 85.5708487197
-63.215 DESIRED_RUDDER iJoystick 1.02847376934
-63.223 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.3702,19.5830,-0.9059},Vel=[3x1]{-0.9263,-0.7261,2.0513},Raw=[2x1]{21.5470,-0.9059},time=1225719874.87048888206482,Speed=1.17695160772174,Pitch=0.03365030600758,Roll=0.02467689107222,PitchDot=0.05384048961213,RollDot=0.00085247441886
-63.223 ODOMETRY_POSE iPlatform Pose=[3x1]{5.3702,19.5830,-0.9055},Vel=[3x1]{-0.9263,-0.7261,2.0507},Raw=[2x1]{21.5470,-0.9059},time=1225719874.8705,Speed=1.1770,Pitch=0.0014,Roll=0.0417,PitchDot=-0.0241,RollDot=-0.0481
-63.202 LMS_LASER_2D_RIGHT LMS2 ID=4017,time=1225719874.841033,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=106,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.805,18.335,14.931,12.466,10.787,9.693,8.819,8.004,7.267,6.758,6.246,5.812,5.476,5.156,4.818,4.552,4.313,4.069,3.851,3.651,3.470,3.322,3.166,3.042,2.924,2.757,2.626,2.570,2.505,2.423,2.346,2.274,2.209,2.145,2.092,2.044,1.975,1.904,1.864,1.824,1.759,1.711,1.689,1.653,1.623,1.583,1.559,1.531,1.497,1.488,1.446,1.414,1.391,1.350,1.315,1.297,1.296,1.262,1.246,1.232,1.227,1.224,1.216,1.222,1.234,1.238,1.231,1.234,1.229,1.206,1.191,1.187,1.178,1.163,1.152,1.143,1.135,1.116,1.108,1.095,1.088,1.080,1.069,1.054,1.048,1.059,1.043,1.046,1.027,1.026},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,43.000,26.000,126.000,101.000,82.000,63.000,57.000,56.000,55.000,62.000,68.000,66.000,67.000,69.000,71.000,72.000,74.000,75.000,76.000,76.000,78.000,77.000,78.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,80.000,79.000,78.000,80.000,80.000,79.000,78.000,79.000,79.000,78.000,77.000,78.000,78.000,75.000,66.000,68.000,77.000,75.000,71.000,74.000,73.000,71.000,73.000,77.000,78.000,79.000,78.000,76.000,65.000,53.000,51.000,55.000,61.000,62.000,66.000,70.000,63.000,55.000,56.000,54.000,51.000,47.000,41.000,43.000,40.000,31.000,32.000,35.000,31.000,31.000,41.000,44.000,40.000,42.000,41.000}
-63.206 LMS_LASER_2D_LEFT LMS1 ID=4145,time=1225719874.848809,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=142,Range=[181]{1.023,1.034,1.037,1.039,1.051,1.060,1.067,1.079,1.082,1.091,1.112,1.120,1.127,1.144,1.156,1.163,1.172,1.187,1.200,1.210,1.222,1.240,1.254,1.262,1.273,1.283,1.303,1.329,1.343,1.369,1.394,1.414,1.439,1.473,1.497,1.521,1.548,1.579,1.600,1.624,1.653,1.669,1.684,1.715,1.740,1.768,1.817,1.853,1.875,1.920,1.966,1.999,2.049,2.102,2.151,2.192,2.211,2.268,2.364,2.431,2.494,2.574,2.633,2.670,2.673,2.672,2.770,2.878,2.948,3.029,3.110,3.244,3.329,3.408,3.552,3.707,3.803,3.935,4.001,3.999,3.992,4.035,4.058,4.067,4.077,4.068,4.078,4.079,4.071,4.104,4.143,4.169,4.169,4.173,4.192,4.189,4.188,4.191,4.191,4.199,4.199,4.208,4.209,4.215,4.208,4.226,4.226,4.234,4.234,4.244,4.249,4.258,4.260,4.270,4.278,4.287,4.295,4.305,4.318,4.339,2.543,2.566,2.495,2.492,2.476,2.580,2.578,2.644,2.681,2.984,2.869,2.727,2.602,2.629,2.679,2.917,3.209,2.859,2.734,4.616,4.636,4.659,4.680,4.700,4.720,4.739,4.760,4.785,4.807,4.833,4.860,4.885,4.909,4.925,4.958,4.992,5.025,5.051,5.069,5.107,5.137,5.165,5.200,5.223,5.266,5.297,5.327,5.366,5.410,3.253,3.268,3.333,3.250,3.254,3.257,3.257,3.277,3.284,3.302,3.309,3.326},Reflectance=[181]{42.000,39.000,40.000,42.000,43.000,39.000,43.000,40.000,42.000,42.000,40.000,37.000,39.000,39.000,40.000,37.000,40.000,40.000,41.000,43.000,44.000,40.000,43.000,48.000,49.000,53.000,50.000,54.000,48.000,51.000,47.000,49.000,44.000,39.000,36.000,38.000,45.000,39.000,40.000,39.000,41.000,49.000,52.000,49.000,50.000,54.000,36.000,35.000,53.000,42.000,36.000,47.000,38.000,36.000,35.000,40.000,58.000,51.000,43.000,40.000,46.000,46.000,48.000,48.000,53.000,56.000,52.000,47.000,48.000,49.000,47.000,48.000,45.000,46.000,49.000,53.000,66.000,68.000,58.000,61.000,69.000,74.000,75.000,75.000,73.000,70.000,69.000,69.000,69.000,71.000,72.000,74.000,76.000,75.000,76.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,80.000,79.000,78.000,78.000,79.000,79.000,79.000,80.000,80.000,79.000,79.000,78.000,79.000,79.000,78.000,77.000,78.000,48.000,95.000,75.000,74.000,74.000,86.000,76.000,93.000,37.000,103.000,81.000,84.000,70.000,69.000,68.000,91.000,104.000,107.000,41.000,77.000,78.000,77.000,76.000,76.000,77.000,78.000,76.000,76.000,78.000,77.000,78.000,78.000,77.000,77.000,76.000,76.000,75.000,75.000,73.000,72.000,73.000,71.000,71.000,70.000,69.000,68.000,66.000,67.000,69.000,25.000,54.000,103.000,76.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000}
-63.214 LMS_LASER_2D_RIGHT LMS2 ID=4018,time=1225719874.854378,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=107,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.561,18.025,14.651,12.344,10.702,9.628,8.763,7.882,7.232,6.724,6.217,5.786,5.440,5.129,4.791,4.518,4.293,4.065,3.839,3.637,3.451,3.319,3.159,3.042,2.933,2.773,2.634,2.559,2.485,2.424,2.355,2.273,2.192,2.113,2.078,2.037,1.966,1.902,1.856,1.821,1.763,1.723,1.680,1.654,1.632,1.584,1.556,1.515,1.484,1.465,1.437,1.408,1.379,1.368,1.335,1.314,1.288,1.268,1.247,1.232,1.227,1.224,1.213,1.215,1.222,1.248,1.242,1.242,1.233,1.216,1.214,1.190,1.171,1.153,1.155,1.144,1.146,1.123,1.105,1.095,1.097,1.094,1.074,1.063,1.069,1.050,1.049,1.042,1.025,1.019},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,20.000,45.000,118.000,98.000,80.000,62.000,57.000,57.000,55.000,63.000,67.000,68.000,67.000,69.000,71.000,72.000,74.000,74.000,75.000,76.000,78.000,79.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,80.000,79.000,78.000,78.000,79.000,80.000,78.000,78.000,77.000,76.000,77.000,72.000,69.000,75.000,74.000,71.000,74.000,72.000,71.000,75.000,77.000,78.000,79.000,78.000,75.000,68.000,59.000,47.000,48.000,40.000,52.000,60.000,60.000,56.000,59.000,63.000,52.000,48.000,39.000,40.000,42.000,42.000,40.000,39.000,36.000,32.000,35.000,34.000,41.000,44.000,39.000,35.000}
-63.214 LMS_LASER_2D_RIGHT LMS2 ID=4019,time=1225719874.867709,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=108,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.772,17.355,14.226,12.031,10.553,9.534,8.655,7.807,7.144,6.651,6.174,5.724,5.389,5.085,4.740,4.483,4.256,4.044,3.812,3.619,3.424,3.276,3.136,3.029,2.909,2.788,2.636,2.541,2.477,2.409,2.337,2.255,2.174,2.090,2.062,2.019,1.950,1.906,1.858,1.818,1.760,1.730,1.689,1.653,1.620,1.589,1.553,1.518,1.475,1.457,1.429,1.407,1.386,1.363,1.329,1.304,1.281,1.270,1.253,1.239,1.224,1.212,1.205,1.222,1.227,1.235,1.234,1.238,1.246,1.220,1.210,1.182,1.170,1.161,1.165,1.148,1.137,1.116,1.094,1.090,1.088,1.079,1.073,1.069,1.057,1.057,1.051,1.037,1.033,1.024},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,49.000,66.000,121.000,94.000,79.000,60.000,57.000,57.000,54.000,63.000,67.000,69.000,68.000,69.000,70.000,72.000,74.000,74.000,75.000,77.000,78.000,80.000,78.000,81.000,81.000,81.000,81.000,80.000,80.000,81.000,81.000,80.000,80.000,81.000,80.000,80.000,79.000,79.000,80.000,78.000,77.000,78.000,79.000,79.000,78.000,77.000,76.000,77.000,74.000,74.000,71.000,74.000,72.000,63.000,67.000,70.000,74.000,76.000,76.000,77.000,78.000,77.000,75.000,66.000,61.000,49.000,49.000,38.000,41.000,50.000,53.000,57.000,63.000,62.000,52.000,52.000,37.000,36.000,39.000,38.000,45.000,35.000,38.000,39.000,34.000,36.000,43.000,42.000,43.000,43.000}
-63.218 LMS_LASER_2D_LEFT LMS1 ID=4146,time=1225719874.862149,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=143,Range=[181]{1.019,1.031,1.034,1.047,1.056,1.056,1.065,1.083,1.088,1.095,1.119,1.121,1.112,1.140,1.140,1.163,1.176,1.189,1.196,1.218,1.225,1.233,1.254,1.259,1.277,1.284,1.316,1.327,1.351,1.374,1.391,1.407,1.432,1.462,1.494,1.527,1.548,1.575,1.604,1.625,1.653,1.667,1.689,1.725,1.753,1.775,1.811,1.853,1.889,1.919,1.971,2.006,2.057,2.103,2.158,2.194,2.241,2.285,2.357,2.423,2.498,2.582,2.648,2.681,2.668,2.680,2.780,2.874,2.960,3.040,3.118,3.246,3.345,3.433,3.580,3.749,3.802,3.930,4.007,3.990,3.996,4.035,4.059,4.070,4.071,4.076,4.083,4.081,4.071,4.096,4.145,4.170,4.167,4.173,4.194,4.189,4.191,4.191,4.191,4.199,4.205,4.206,4.208,4.209,4.218,4.225,4.226,4.234,4.234,4.237,4.248,4.255,4.261,4.270,4.284,4.281,4.295,4.314,2.630,2.722,2.531,2.506,2.528,2.493,2.488,2.521,2.561,2.710,2.941,2.830,2.619,2.592,2.622,2.668,2.843,3.188,2.941,2.809,2.831,4.617,4.634,4.659,4.681,4.698,4.729,4.746,4.765,4.792,4.813,4.835,4.859,4.876,4.910,4.936,4.961,4.999,5.027,5.051,5.070,5.105,5.133,5.173,5.199,5.232,5.266,5.304,3.203,3.221,3.242,3.325,3.231,3.225,3.230,3.238,3.249,3.260,3.279,3.292,3.301,3.318,3.334},Reflectance=[181]{40.000,42.000,39.000,41.000,42.000,46.000,41.000,38.000,41.000,44.000,39.000,34.000,31.000,34.000,33.000,40.000,43.000,40.000,44.000,42.000,45.000,46.000,43.000,50.000,50.000,53.000,48.000,53.000,48.000,46.000,50.000,53.000,53.000,47.000,40.000,44.000,45.000,41.000,38.000,36.000,40.000,48.000,54.000,45.000,47.000,53.000,40.000,39.000,40.000,46.000,45.000,47.000,42.000,37.000,41.000,45.000,51.000,54.000,44.000,46.000,43.000,49.000,50.000,49.000,51.000,56.000,53.000,46.000,46.000,47.000,46.000,49.000,46.000,49.000,53.000,57.000,66.000,63.000,57.000,62.000,70.000,74.000,76.000,76.000,74.000,73.000,70.000,69.000,69.000,71.000,72.000,75.000,76.000,75.000,77.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,78.000,18.000,114.000,78.000,75.000,79.000,76.000,75.000,72.000,71.000,120.000,118.000,85.000,77.000,69.000,73.000,70.000,89.000,108.000,32.000,90.000,32.000,78.000,77.000,77.000,76.000,76.000,77.000,77.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,76.000,75.000,71.000,71.000,72.000,70.000,68.000,70.000,69.000,67.000,22.000,22.000,43.000,104.000,76.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000}
-63.228 LMS_LASER_2D_RIGHT LMS2 ID=4020,time=1225719874.881041,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=109,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.412,16.895,13.913,11.818,10.415,9.428,8.566,7.752,7.074,6.581,6.072,5.647,5.336,5.033,4.672,4.447,4.239,4.005,3.771,3.610,3.417,3.274,3.106,3.009,2.884,2.770,2.643,2.542,2.469,2.406,2.319,2.224,2.165,2.087,2.054,1.985,1.925,1.884,1.841,1.803,1.768,1.725,1.688,1.647,1.584,1.568,1.539,1.509,1.475,1.440,1.429,1.407,1.379,1.346,1.322,1.297,1.288,1.263,1.255,1.238,1.223,1.212,1.210,1.214,1.229,1.236,1.250,1.246,1.234,1.224,1.188,1.178,1.171,1.164,1.162,1.156,1.137,1.112,1.102,1.090,1.088,1.045,1.068,1.070,1.059,1.016,1.036,1.039,1.032,1.028},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,23.000,80.000,118.000,91.000,75.000,59.000,57.000,56.000,54.000,64.000,68.000,69.000,69.000,69.000,72.000,72.000,73.000,76.000,76.000,77.000,78.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,79.000,77.000,75.000,75.000,77.000,73.000,73.000,76.000,76.000,77.000,73.000,65.000,70.000,73.000,76.000,77.000,77.000,77.000,78.000,77.000,74.000,67.000,54.000,50.000,44.000,41.000,35.000,44.000,59.000,63.000,60.000,56.000,48.000,48.000,39.000,45.000,43.000,42.000,37.000,27.000,36.000,44.000,43.000,28.000,40.000,40.000,41.000,37.000}
-63.239 DESIRED_THRUST iJoystick 85.5708487197
-63.239 DESIRED_RUDDER iJoystick 1.02847376934
-63.232 LMS_LASER_2D_LEFT LMS1 ID=4147,time=1225719874.875490,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=144,Range=[181]{1.026,1.031,1.041,1.041,1.054,1.062,1.073,1.078,1.084,1.095,1.116,1.120,1.125,1.129,1.166,1.166,1.172,1.191,1.192,1.206,1.225,1.241,1.252,1.266,1.289,1.306,1.322,1.334,1.355,1.380,1.390,1.417,1.441,1.474,1.503,1.516,1.557,1.579,1.600,1.625,1.644,1.671,1.690,1.721,1.756,1.776,1.814,1.861,1.896,1.951,1.980,2.025,2.054,2.116,2.155,2.210,2.258,2.305,2.337,2.426,2.501,2.596,2.635,2.674,2.664,2.692,2.820,2.886,2.966,3.043,3.124,3.260,3.366,3.442,3.582,3.745,3.820,3.973,3.999,3.990,3.998,4.044,4.055,4.067,4.072,4.065,4.086,4.084,4.074,4.111,4.146,4.174,4.159,4.181,4.186,4.189,4.189,4.191,4.191,4.199,4.195,4.207,4.207,4.217,4.215,4.223,4.226,4.234,4.235,4.246,4.246,4.255,4.263,4.269,4.278,4.286,4.295,4.312,2.725,2.590,2.596,2.587,2.574,2.473,2.508,2.572,2.706,2.765,2.915,2.667,2.592,2.623,2.683,2.851,3.102,3.017,3.020,2.864,4.600,4.617,4.642,4.658,4.684,4.703,4.729,4.746,4.770,4.785,4.813,4.832,4.859,4.885,4.910,4.943,4.969,4.995,5.035,5.056,5.073,5.099,5.138,5.168,5.201,5.238,5.262,3.199,3.176,3.303,3.212,3.205,3.208,3.210,3.221,3.230,3.248,3.257,3.282,3.298,3.316,3.324,3.341},Reflectance=[181]{39.000,38.000,38.000,36.000,41.000,40.000,42.000,40.000,43.000,44.000,41.000,40.000,34.000,33.000,38.000,42.000,46.000,45.000,47.000,46.000,45.000,46.000,47.000,46.000,43.000,43.000,51.000,52.000,53.000,49.000,53.000,54.000,49.000,39.000,46.000,48.000,42.000,39.000,41.000,45.000,50.000,50.000,50.000,52.000,52.000,53.000,42.000,39.000,36.000,40.000,42.000,43.000,46.000,45.000,44.000,40.000,35.000,55.000,55.000,47.000,45.000,56.000,56.000,50.000,53.000,57.000,48.000,47.000,49.000,48.000,49.000,51.000,47.000,49.000,54.000,59.000,66.000,57.000,57.000,62.000,71.000,74.000,75.000,75.000,74.000,72.000,71.000,70.000,67.000,70.000,75.000,76.000,76.000,76.000,77.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,117.000,76.000,76.000,76.000,81.000,73.000,74.000,77.000,108.000,34.000,110.000,80.000,72.000,70.000,75.000,89.000,101.000,38.000,103.000,111.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,75.000,76.000,74.000,72.000,69.000,70.000,69.000,69.000,69.000,68.000,45.000,60.000,108.000,78.000,76.000,77.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000}
-63.242 LMS_LASER_2D_RIGHT LMS2 ID=4021,time=1225719874.894373,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=110,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.376,16.405,13.580,11.494,10.169,9.222,8.429,7.602,6.967,6.496,6.007,5.596,5.238,4.972,4.639,4.385,4.185,3.940,3.745,3.578,3.392,3.220,3.095,2.966,2.856,2.750,2.626,2.533,2.469,2.388,2.275,2.199,2.165,2.103,2.038,1.966,1.931,1.872,1.839,1.786,1.740,1.707,1.680,1.637,1.612,1.569,1.530,1.503,1.469,1.440,1.409,1.388,1.369,1.341,1.323,1.295,1.270,1.253,1.238,1.224,1.216,1.210,1.199,1.212,1.222,1.236,1.233,1.237,1.231,1.201,1.171,1.165,1.162,1.158,1.151,1.145,1.132,1.091,1.089,1.090,1.043,1.058,1.072,1.067,1.049,1.044,1.029,1.037,1.030,1.011},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,97.000,112.000,90.000,72.000,59.000,56.000,56.000,56.000,64.000,67.000,68.000,70.000,70.000,71.000,73.000,74.000,75.000,75.000,77.000,77.000,78.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,77.000,80.000,80.000,81.000,79.000,79.000,79.000,80.000,80.000,79.000,79.000,79.000,74.000,75.000,76.000,77.000,77.000,75.000,74.000,75.000,77.000,76.000,72.000,71.000,70.000,71.000,76.000,77.000,78.000,78.000,77.000,70.000,63.000,51.000,46.000,45.000,41.000,39.000,53.000,65.000,67.000,63.000,61.000,58.000,51.000,38.000,38.000,40.000,36.000,27.000,29.000,38.000,47.000,50.000,37.000,32.000,40.000,40.000,35.000}
-63.246 LMS_LASER_2D_LEFT LMS1 ID=4148,time=1225719874.888831,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=145,Range=[181]{1.024,1.032,1.038,1.047,1.048,1.057,1.071,1.078,1.082,1.094,1.111,1.126,1.137,1.143,1.156,1.162,1.174,1.182,1.195,1.216,1.226,1.238,1.252,1.280,1.287,1.296,1.316,1.334,1.353,1.379,1.392,1.422,1.449,1.476,1.504,1.536,1.555,1.578,1.602,1.620,1.649,1.668,1.699,1.717,1.756,1.791,1.823,1.869,1.908,1.949,1.988,2.027,2.058,2.114,2.161,2.218,2.271,2.318,2.339,2.435,2.510,2.605,2.651,2.675,2.669,2.689,2.835,2.890,2.971,3.053,3.135,3.272,3.380,3.459,3.618,3.778,3.871,3.999,3.998,3.981,4.011,4.044,4.058,4.067,4.068,4.069,4.082,4.081,4.067,4.106,4.147,4.172,4.165,4.181,4.186,4.189,4.189,4.191,4.191,4.198,4.198,4.206,4.206,4.215,4.214,4.224,4.225,4.234,4.233,4.243,4.252,4.260,4.269,4.277,4.278,4.287,4.294,2.613,2.684,2.592,2.597,2.596,2.538,2.497,2.520,2.704,2.891,2.820,2.781,2.657,2.620,2.682,2.874,2.833,3.037,2.956,2.986,3.015,4.600,4.617,4.642,4.660,4.685,4.705,4.730,4.748,4.771,4.793,4.813,4.841,4.858,4.884,4.918,4.941,4.967,4.997,5.039,5.049,5.077,5.110,5.143,5.166,5.212,3.158,3.163,3.164,3.162,3.169,3.179,3.190,3.204,3.204,3.221,3.230,3.247,3.263,3.288,3.304,3.321,3.339,3.352},Reflectance=[181]{36.000,42.000,37.000,41.000,47.000,42.000,40.000,44.000,47.000,44.000,39.000,43.000,40.000,39.000,37.000,44.000,45.000,46.000,48.000,45.000,47.000,49.000,47.000,43.000,47.000,51.000,48.000,48.000,49.000,52.000,54.000,49.000,44.000,40.000,41.000,40.000,45.000,43.000,41.000,48.000,49.000,53.000,46.000,54.000,49.000,52.000,42.000,38.000,37.000,43.000,41.000,44.000,47.000,38.000,42.000,36.000,40.000,54.000,55.000,47.000,46.000,56.000,56.000,50.000,55.000,56.000,47.000,49.000,47.000,49.000,50.000,52.000,46.000,49.000,50.000,55.000,64.000,58.000,57.000,63.000,72.000,74.000,75.000,75.000,73.000,73.000,72.000,69.000,68.000,69.000,70.000,75.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,28.000,105.000,77.000,76.000,76.000,81.000,73.000,72.000,98.000,113.000,91.000,76.000,77.000,72.000,74.000,88.000,33.000,37.000,36.000,96.000,16.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,77.000,76.000,72.000,74.000,72.000,70.000,70.000,69.000,66.000,69.000,22.000,58.000,77.000,79.000,76.000,76.000,77.000,79.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000}
-63.259 LMS_LASER_2D_LEFT LMS1 ID=4149,time=1225719874.902172,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=146,Range=[181]{1.029,1.035,1.043,1.060,1.055,1.065,1.069,1.084,1.090,1.099,1.112,1.125,1.130,1.154,1.166,1.166,1.181,1.194,1.203,1.214,1.226,1.243,1.259,1.273,1.287,1.303,1.322,1.345,1.363,1.382,1.406,1.428,1.457,1.481,1.513,1.536,1.559,1.575,1.608,1.624,1.650,1.671,1.698,1.722,1.764,1.783,1.823,1.871,1.911,1.957,1.994,2.023,2.073,2.122,2.168,2.223,2.276,2.324,2.362,2.459,2.517,2.585,2.670,2.667,2.662,2.702,2.840,2.899,2.972,3.061,3.155,3.277,3.397,3.466,3.674,3.819,3.904,3.998,3.996,3.981,4.012,4.048,4.069,4.066,4.071,4.071,4.088,4.072,4.078,4.112,4.146,4.164,4.164,4.182,4.180,4.190,4.191,4.191,4.191,4.198,4.204,4.207,4.208,4.207,4.215,4.223,4.231,4.231,4.241,4.243,4.252,4.260,4.269,4.278,4.278,4.289,4.296,2.606,2.714,2.664,2.681,2.595,2.549,2.525,2.673,2.684,2.803,2.727,2.761,2.803,2.691,3.003,3.188,3.041,3.119,3.067,3.070,4.592,4.599,4.625,4.644,4.661,4.685,4.705,4.730,4.748,4.771,4.795,4.823,4.842,4.867,4.899,4.917,4.950,4.974,5.001,5.036,5.055,5.090,5.116,5.149,3.125,3.143,3.222,3.136,3.137,3.148,3.153,3.173,3.185,3.195,3.213,3.221,3.237,3.253,3.278,3.294,3.321,3.336,3.347,3.376},Reflectance=[181]{40.000,44.000,44.000,39.000,37.000,42.000,44.000,39.000,42.000,41.000,44.000,42.000,41.000,40.000,38.000,42.000,45.000,48.000,48.000,46.000,47.000,47.000,50.000,49.000,47.000,50.000,47.000,49.000,49.000,49.000,49.000,51.000,44.000,34.000,42.000,44.000,48.000,51.000,45.000,50.000,49.000,54.000,54.000,53.000,52.000,52.000,47.000,43.000,38.000,43.000,41.000,51.000,46.000,46.000,46.000,34.000,41.000,53.000,47.000,45.000,53.000,55.000,51.000,50.000,56.000,58.000,53.000,49.000,51.000,52.000,47.000,50.000,46.000,47.000,50.000,61.000,63.000,57.000,59.000,66.000,72.000,75.000,76.000,75.000,74.000,74.000,71.000,69.000,69.000,68.000,70.000,75.000,75.000,76.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,27.000,115.000,94.000,93.000,82.000,85.000,73.000,87.000,46.000,104.000,74.000,73.000,75.000,74.000,85.000,108.000,27.000,101.000,107.000,116.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,71.000,73.000,69.000,69.000,69.000,66.000,27.000,49.000,101.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,76.000,77.000,76.000,77.000,75.000}
-63.259 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.4068,19.6116,-0.9093},Vel=[3x1]{-0.9229,-0.7186,0.1282},Raw=[2x1]{21.5935,-0.9093},time=1225719874.90639805793762,Speed=1.16965041908823,Pitch=0.03589365974142,Roll=0.02916359853990,PitchDot=0.05159713587829,RollDot=0.00125627809095
-63.259 ODOMETRY_POSE iPlatform Pose=[3x1]{5.4068,19.6116,-0.9088},Vel=[3x1]{-0.9229,-0.7186,0.1284},Raw=[2x1]{21.5935,-0.9093},time=1225719874.9064,Speed=1.1697,Pitch=-0.0009,Roll=0.0462,PitchDot=0.0513,RollDot=-0.0054
-63.259 VEHICLE_GEOMETRY iPlatform Name=LISA, Sensor_0=LMS_LASER_2D, Pose3D_0=[4x1]{0.0000,0.3500,0.0000,0.0000},SHAPE_2D=[2x8]{0.3300,0.3300,0.2100,0.2100,-0.2100,-0.2100,-0.3300,-0.3300,-0.4100,0.4100,0.4100,0.5700,0.5700,0.4100,0.4100,-0.4100,}
-63.263 IJOYSTICK_STATUS iJoystick AppErrorFlag=false,Uptime=62.914,MOOSName=iJoystick,Publishing=COLLISION_OK,DESIRED_RUDDER,DESIRED_THRUST,IJOYSTICK_STATUS,Subscribing=
-63.263 DESIRED_THRUST iJoystick 85.5708487197
-63.263 DESIRED_RUDDER iJoystick 1.02847376934
-63.254 LMS_LASER_2D_RIGHT LMS2 ID=4022,time=1225719874.907703,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=111,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.511,-1.000,15.955,12.942,11.127,9.970,9.057,8.263,7.434,6.850,6.375,5.911,5.511,5.201,4.873,4.561,4.313,4.126,3.888,3.698,3.516,3.362,3.185,3.050,2.941,2.840,2.714,2.607,2.541,2.448,2.371,2.271,2.197,2.147,2.095,2.044,1.967,1.915,1.864,1.813,1.768,1.731,1.695,1.671,1.631,1.601,1.564,1.532,1.502,1.467,1.439,1.411,1.378,1.354,1.332,1.313,1.286,1.254,1.244,1.229,1.212,1.210,1.199,1.205,1.222,1.212,1.223,1.226,1.236,1.218,1.175,1.163,1.157,1.154,1.154,1.162,1.142,1.115,1.095,1.086,1.082,1.046,1.038,1.064,1.061,1.043,1.043,0.996,1.013,1.019,1.013},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,0.000,109.000,117.000,85.000,67.000,58.000,55.000,57.000,61.000,66.000,67.000,68.000,69.000,71.000,72.000,74.000,74.000,75.000,74.000,78.000,78.000,79.000,79.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,78.000,79.000,78.000,77.000,77.000,78.000,77.000,77.000,76.000,76.000,76.000,75.000,72.000,70.000,69.000,74.000,76.000,77.000,77.000,76.000,70.000,64.000,51.000,36.000,39.000,37.000,38.000,46.000,61.000,65.000,69.000,64.000,59.000,48.000,34.000,31.000,40.000,39.000,36.000,28.000,25.000,32.000,52.000,55.000,44.000,27.000,32.000,42.000,38.000}
-63.270 LMS_LASER_2D_LEFT LMS1 ID=4150,time=1225719874.915510,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=147,Range=[181]{1.031,1.035,1.045,1.049,1.056,1.071,1.081,1.086,1.084,1.098,1.111,1.118,1.140,1.149,1.158,1.177,1.188,1.189,1.208,1.217,1.233,1.254,1.264,1.272,1.292,1.312,1.336,1.348,1.371,1.389,1.407,1.428,1.464,1.494,1.512,1.540,1.565,1.565,1.603,1.637,1.655,1.680,1.699,1.737,1.764,1.800,1.837,1.876,1.923,1.963,2.005,2.037,2.081,2.133,2.179,2.237,2.292,2.333,2.383,2.462,2.532,2.594,2.669,2.668,2.667,2.717,2.853,2.892,2.972,3.064,3.182,3.310,3.406,3.498,3.700,3.826,3.922,3.990,3.981,3.988,4.021,4.054,4.067,4.072,4.068,4.080,4.084,4.068,4.080,4.121,4.160,4.167,4.165,4.191,4.187,4.188,4.191,4.190,4.199,4.199,4.208,4.203,4.222,4.217,4.212,4.222,4.229,4.243,4.238,4.243,4.250,4.259,4.269,4.277,4.278,4.289,4.307,2.659,2.701,2.678,2.802,2.511,2.525,2.697,2.786,2.754,2.811,2.745,2.794,2.765,2.839,3.048,3.211,3.160,3.039,3.055,3.123,4.593,4.608,4.633,4.645,4.669,4.685,4.713,4.730,4.756,4.771,4.796,4.825,4.850,4.875,4.898,4.924,4.957,4.982,5.010,5.028,5.060,5.090,3.129,3.110,3.196,3.134,3.111,3.115,3.123,3.136,3.157,3.168,3.186,3.194,3.210,3.228,3.253,3.270,3.292,3.317,3.343,3.371,3.367,3.402},Reflectance=[181]{42.000,44.000,40.000,47.000,42.000,41.000,41.000,44.000,48.000,45.000,48.000,43.000,41.000,45.000,42.000,43.000,44.000,46.000,46.000,47.000,46.000,43.000,44.000,48.000,49.000,45.000,44.000,46.000,44.000,49.000,50.000,47.000,39.000,41.000,46.000,41.000,54.000,58.000,48.000,47.000,51.000,54.000,54.000,48.000,52.000,52.000,49.000,45.000,43.000,41.000,46.000,46.000,46.000,42.000,36.000,46.000,42.000,49.000,47.000,48.000,55.000,55.000,51.000,51.000,58.000,57.000,51.000,49.000,55.000,58.000,47.000,45.000,49.000,50.000,54.000,60.000,64.000,62.000,64.000,68.000,72.000,74.000,75.000,74.000,73.000,74.000,70.000,68.000,69.000,68.000,72.000,76.000,75.000,76.000,77.000,78.000,79.000,78.000,79.000,79.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,19.000,21.000,43.000,104.000,75.000,73.000,84.000,97.000,38.000,104.000,74.000,78.000,75.000,73.000,84.000,113.000,114.000,76.000,104.000,5.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,78.000,77.000,77.000,76.000,77.000,76.000,76.000,74.000,71.000,68.000,67.000,38.000,59.000,100.000,81.000,77.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,76.000,79.000,75.000,75.000}
-63.278 LMS_LASER_2D_RIGHT LMS2 ID=4023,time=1225719874.921045,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=112,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.998,18.333,15.189,12.664,10.792,9.740,8.872,8.025,7.241,6.720,6.271,5.795,5.441,5.129,4.792,4.510,4.265,4.093,3.826,3.656,3.469,3.327,3.156,3.041,2.915,2.786,2.670,2.587,2.504,2.423,2.351,2.261,2.192,2.122,2.078,2.019,1.961,1.908,1.856,1.804,1.750,1.724,1.688,1.652,1.610,1.573,1.554,1.520,1.483,1.452,1.432,1.405,1.377,1.354,1.305,1.283,1.268,1.257,1.247,1.227,1.218,1.205,1.201,1.207,1.219,1.220,1.219,1.218,1.224,1.187,1.161,1.154,1.153,1.154,1.141,1.145,1.137,1.120,1.094,1.081,1.080,1.053,1.034,1.065,1.046,1.037,1.042,1.029,1.026,1.024,1.002},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,33.000,16.000,124.000,102.000,83.000,64.000,57.000,57.000,55.000,61.000,67.000,69.000,69.000,69.000,71.000,72.000,73.000,74.000,74.000,74.000,78.000,79.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,75.000,74.000,77.000,77.000,76.000,77.000,76.000,76.000,76.000,75.000,72.000,75.000,75.000,78.000,77.000,77.000,76.000,75.000,72.000,68.000,54.000,50.000,47.000,50.000,48.000,55.000,62.000,66.000,64.000,65.000,72.000,63.000,51.000,44.000,41.000,40.000,40.000,29.000,26.000,41.000,56.000,56.000,47.000,37.000,39.000,41.000,35.000}
-63.282 LMS_LASER_2D_LEFT LMS1 ID=4151,time=1225719874.928848,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=148,Range=[181]{1.033,1.034,1.041,1.054,1.060,1.069,1.082,1.089,1.094,1.111,1.116,1.131,1.136,1.151,1.157,1.170,1.191,1.202,1.204,1.226,1.233,1.256,1.266,1.278,1.303,1.319,1.330,1.352,1.372,1.387,1.410,1.434,1.462,1.478,1.502,1.530,1.549,1.563,1.598,1.642,1.667,1.685,1.714,1.743,1.776,1.808,1.839,1.876,1.916,1.971,2.007,2.047,2.099,2.146,2.190,2.248,2.309,2.353,2.407,2.472,2.558,2.633,2.676,2.671,2.680,2.762,2.866,2.918,2.987,3.080,3.200,3.304,3.405,3.516,3.732,3.862,3.935,3.987,3.982,3.990,4.033,4.055,4.066,4.072,4.063,4.077,4.085,4.062,4.088,4.134,4.166,4.165,4.172,4.183,4.187,4.190,4.189,4.191,4.190,4.196,4.203,4.211,4.219,4.216,4.221,4.227,4.230,4.239,4.249,4.251,4.250,4.259,4.267,4.276,4.286,2.829,2.775,2.756,2.794,2.812,2.638,2.592,2.650,2.717,2.899,2.775,2.760,2.767,2.740,2.773,2.846,3.053,3.197,3.138,3.052,3.174,4.576,4.592,4.616,4.635,4.645,4.668,4.693,4.714,4.738,4.757,4.779,4.808,4.832,4.859,4.882,4.906,4.933,4.968,4.991,5.015,5.034,3.111,3.215,3.160,3.093,3.096,3.103,3.105,3.115,3.129,3.138,3.157,3.175,3.191,3.202,3.225,3.243,3.258,3.290,3.316,3.361,3.440,3.479,3.402,3.425},Reflectance=[181]{43.000,39.000,43.000,41.000,44.000,44.000,41.000,45.000,44.000,39.000,41.000,41.000,44.000,43.000,46.000,44.000,45.000,43.000,49.000,47.000,46.000,44.000,46.000,47.000,45.000,46.000,46.000,48.000,40.000,48.000,51.000,50.000,47.000,54.000,53.000,54.000,59.000,63.000,50.000,40.000,48.000,52.000,49.000,47.000,50.000,51.000,50.000,46.000,52.000,45.000,47.000,50.000,41.000,44.000,44.000,46.000,41.000,45.000,45.000,48.000,45.000,55.000,50.000,52.000,60.000,53.000,46.000,46.000,51.000,57.000,47.000,47.000,49.000,50.000,53.000,62.000,70.000,70.000,67.000,69.000,74.000,75.000,75.000,74.000,74.000,73.000,70.000,69.000,69.000,69.000,73.000,75.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,77.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,122.000,112.000,103.000,105.000,104.000,87.000,67.000,72.000,74.000,111.000,39.000,78.000,75.000,72.000,74.000,72.000,83.000,116.000,103.000,75.000,111.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,77.000,78.000,77.000,78.000,77.000,76.000,77.000,77.000,76.000,75.000,68.000,38.000,109.000,92.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,76.000,75.000,75.000,79.000,88.000,103.000,59.000,63.000}
-63.283 DESIRED_THRUST iJoystick 85.5708487197
-63.283 DESIRED_RUDDER iJoystick 1.02847376934
-63.290 LMS_LASER_2D_RIGHT LMS2 ID=4024,time=1225719874.934386,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=113,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.763,17.544,14.516,12.247,10.570,9.571,8.714,7.837,7.138,6.634,6.146,5.698,5.337,5.024,4.732,4.448,4.221,4.026,3.774,3.616,3.441,3.281,3.112,3.019,2.883,2.735,2.634,2.566,2.486,2.406,2.325,2.237,2.165,2.113,2.070,2.002,1.935,1.882,1.828,1.784,1.736,1.716,1.680,1.648,1.600,1.568,1.536,1.501,1.479,1.449,1.413,1.387,1.371,1.347,1.305,1.290,1.262,1.252,1.250,1.233,1.219,1.210,1.200,1.206,1.218,1.216,1.210,1.212,1.224,1.193,1.163,1.153,1.158,1.136,1.112,1.111,1.108,1.106,1.083,1.077,1.079,1.080,1.065,1.073,1.043,1.038,1.035,1.020,1.028,1.016,1.007},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,45.000,61.000,117.000,98.000,78.000,61.000,56.000,58.000,55.000,64.000,67.000,68.000,69.000,70.000,70.000,73.000,73.000,74.000,73.000,76.000,77.000,78.000,77.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,79.000,79.000,78.000,74.000,75.000,77.000,77.000,75.000,73.000,76.000,76.000,77.000,75.000,72.000,74.000,76.000,78.000,78.000,76.000,74.000,73.000,72.000,66.000,46.000,52.000,57.000,54.000,45.000,54.000,60.000,58.000,61.000,63.000,65.000,64.000,61.000,53.000,41.000,41.000,45.000,48.000,36.000,46.000,55.000,52.000,35.000,35.000,37.000,41.000,38.000}
-63.295 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.4438,19.6403,-0.9111},Vel=[3x1]{-0.9416,-0.7302,-1.6667},Raw=[2x1]{21.6403,-0.9111},time=1225719874.94246888160706,Speed=1.19155398498876,Pitch=0.03813701347526,Roll=0.03140695227374,PitchDot=0.05608384334597,RollDot=0.00174981591239
-63.295 ODOMETRY_POSE iPlatform Pose=[3x1]{5.4438,19.6403,-0.9105},Vel=[3x1]{-0.9416,-0.7302,-1.6665},Raw=[2x1]{21.6403,-0.9111},time=1225719874.9425,Speed=1.1916,Pitch=-0.0014,Roll=0.0494,PitchDot=-0.0071,RollDot=0.0557
-63.307 DESIRED_THRUST iJoystick 85.5708487197
-63.307 DESIRED_RUDDER iJoystick 1.02847376934
-63.320 PLOGGER_STATUS pLogger AppErrorFlag=false,Uptime=63.3202,MOOSName=pLogger,Publishing=LOGGER_DIRECTORY,PLOGGER_STATUS,Subscribing=ANTLER_STATUS,CAMERA_COMMAND,CAMERA_FILE_WRITE,COLLISION_OK,DB_CLIENTS,DB_TIME,DB_UPTIME,DESIRED_ELEVATOR,DESIRED_RUDDER,DESIRED_THRUST,EKF_ENABLE,GPS,ICAMERABUMBLEBEE_STATUS,ICAMERALADYBUG_STATUS,ICAMERA_STATUS,IGPS_STATUS,IJOYSTICK_STATUS,IPLATFORM_CMD,IPLATFORM_STATUS,IRELAYBOX_STATUS,LASER_LAG,LMS1_CMD,LMS1_STATUS,LMS2_CMD,LMS2_STATUS,LMS_LASER_2D_LEFT,LMS_LASER_2D_RIGHT,LOCAL_LASER_LAG,LOGGER_DIRECTORY,LOGGER_RESTART,LSQ_ENABLE,MARGE_ODOMETRY,MISSION_FILE,MOOS_DEBUG,MOOS_MANUAL_OVERIDE,MOOS_SYSTEM,NAV_POSE,NAV_SUMMARY,NAV_SUMMARY_REQUEST,ODOMETRY_POSE,ODOM_UNITS_PER_METER,ODOM_UNITS_PER_RADIAN,PLOGGER_CMD,PLOGGER_STATUS,PLOGSTEREO_CMD,PLOGSTEREO_STATUS,PNAV_STATUS,QUERY_ODOM_CALIBRATION,RELAYBOX_CMD,RELAYBOX_STATUS,RESET_ACTUATION,RESTART_NAV,SET_INTERPOSE_COMMAND,TOP_DOWN_CAL_CONTROL,UWATCHDOG_STATUS,VEHICLE_GEOMETRY,
-63.297 LMS_LASER_2D_LEFT LMS1 ID=4152,time=1225719874.942188,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=149,Range=[181]{1.028,1.043,1.039,1.053,1.057,1.068,1.082,1.084,1.101,1.114,1.122,1.132,1.139,1.158,1.164,1.172,1.191,1.199,1.217,1.230,1.248,1.253,1.268,1.280,1.312,1.324,1.342,1.352,1.375,1.401,1.412,1.439,1.470,1.482,1.505,1.529,1.552,1.578,1.612,1.643,1.670,1.694,1.721,1.757,1.783,1.817,1.845,1.884,1.920,1.962,1.996,2.049,2.090,2.153,2.212,2.251,2.319,2.365,2.426,2.494,2.570,2.616,2.668,2.651,2.673,2.791,2.872,2.919,2.995,3.113,3.219,3.319,3.405,3.553,3.762,3.879,3.955,3.990,3.981,3.995,4.035,4.055,4.064,4.072,4.072,4.082,4.077,4.067,4.097,4.137,4.170,4.156,4.181,4.187,4.188,4.189,4.183,4.191,4.191,4.196,4.206,4.205,4.212,4.219,4.223,4.225,4.226,4.230,4.241,4.250,4.259,4.267,4.266,4.284,2.820,2.682,2.644,2.661,2.681,2.775,2.680,2.635,2.738,2.837,2.773,2.861,2.770,2.779,2.732,2.791,2.904,3.095,3.102,3.145,3.054,3.215,4.576,4.600,4.617,4.633,4.653,4.675,4.695,4.720,4.738,4.765,4.781,4.807,4.832,4.859,4.880,4.914,4.942,4.965,3.070,3.091,3.176,3.091,3.077,3.070,3.079,3.079,3.098,3.107,3.120,3.130,3.149,3.156,3.182,3.201,3.214,3.239,3.257,3.287,3.317,3.428,3.382,3.404,3.422,3.470,3.457},Reflectance=[181]{40.000,39.000,42.000,44.000,47.000,39.000,41.000,43.000,43.000,41.000,41.000,45.000,45.000,41.000,41.000,41.000,46.000,46.000,47.000,40.000,37.000,43.000,46.000,48.000,41.000,43.000,43.000,48.000,45.000,47.000,48.000,48.000,42.000,56.000,54.000,57.000,56.000,56.000,52.000,50.000,49.000,48.000,48.000,49.000,52.000,52.000,52.000,50.000,54.000,54.000,50.000,55.000,47.000,43.000,41.000,47.000,51.000,48.000,47.000,50.000,52.000,56.000,51.000,55.000,62.000,54.000,48.000,47.000,51.000,52.000,48.000,45.000,49.000,53.000,51.000,62.000,73.000,71.000,66.000,70.000,74.000,75.000,75.000,74.000,74.000,72.000,71.000,68.000,69.000,70.000,75.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,76.000,78.000,78.000,79.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,121.000,84.000,76.000,76.000,76.000,105.000,89.000,76.000,81.000,95.000,21.000,109.000,76.000,84.000,73.000,69.000,67.000,102.000,8.000,101.000,76.000,117.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,78.000,76.000,76.000,77.000,76.000,24.000,45.000,105.000,81.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,76.000,76.000,76.000,75.000,76.000,94.000,46.000,33.000,21.000,15.000,27.000}
-63.302 LMS_LASER_2D_RIGHT LMS2 ID=4025,time=1225719874.947724,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=114,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.578,17.000,13.967,11.758,10.268,9.374,8.542,7.643,7.006,6.554,6.052,5.638,5.292,4.936,4.671,4.376,4.177,3.965,3.754,3.572,3.421,3.241,3.102,2.976,2.850,2.705,2.611,2.550,2.468,2.388,2.302,2.219,2.167,2.104,2.044,1.983,1.927,1.859,1.829,1.791,1.731,1.715,1.681,1.638,1.600,1.574,1.536,1.501,1.471,1.440,1.413,1.384,1.347,1.332,1.314,1.288,1.256,1.253,1.243,1.233,1.210,1.202,1.193,1.199,1.216,1.204,1.197,1.197,1.204,1.194,1.179,1.161,1.151,1.126,1.112,1.096,1.095,1.091,1.083,1.074,1.082,1.053,1.030,1.024,1.048,1.045,1.031,1.023,1.021,1.014,1.000},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,30.000,80.000,118.000,94.000,74.000,60.000,54.000,59.000,57.000,64.000,67.000,68.000,70.000,71.000,71.000,73.000,74.000,74.000,75.000,78.000,77.000,77.000,79.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,78.000,79.000,78.000,79.000,79.000,80.000,78.000,77.000,77.000,77.000,77.000,75.000,76.000,76.000,75.000,75.000,72.000,72.000,72.000,75.000,76.000,72.000,69.000,73.000,74.000,73.000,70.000,60.000,64.000,67.000,67.000,55.000,50.000,51.000,55.000,57.000,62.000,65.000,66.000,66.000,58.000,41.000,41.000,41.000,29.000,27.000,28.000,41.000,45.000,36.000,38.000,40.000,42.000,41.000}
-63.314 LMS_LASER_2D_RIGHT LMS2 ID=4026,time=1225719874.961061,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=115,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.130,26.501,16.333,13.151,11.362,10.065,9.171,8.399,7.533,6.919,6.450,5.955,5.568,5.229,4.864,4.588,4.331,4.134,3.893,3.676,3.539,3.376,3.207,3.076,2.949,2.788,2.660,2.591,2.531,2.450,2.353,2.283,2.219,2.157,2.086,2.027,1.970,1.918,1.841,1.815,1.758,1.722,1.698,1.659,1.615,1.593,1.569,1.527,1.492,1.465,1.429,1.401,1.366,1.351,1.330,1.302,1.278,1.252,1.242,1.241,1.225,1.209,1.199,1.194,1.184,1.216,1.207,1.210,1.205,1.195,1.184,1.163,1.154,1.144,1.136,1.123,1.108,1.098,1.097,1.076,1.073,1.081,1.073,1.062,1.013,1.049,1.041,1.021,1.024,1.020,1.005,0.998},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,9.000,8.000,100.000,123.000,89.000,69.000,59.000,54.000,58.000,60.000,64.000,67.000,67.000,69.000,72.000,72.000,73.000,72.000,74.000,78.000,79.000,78.000,77.000,79.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,77.000,80.000,79.000,78.000,79.000,78.000,76.000,78.000,76.000,74.000,73.000,76.000,76.000,75.000,75.000,72.000,68.000,66.000,69.000,71.000,70.000,69.000,69.000,72.000,76.000,77.000,74.000,60.000,60.000,62.000,65.000,63.000,61.000,64.000,65.000,58.000,58.000,60.000,61.000,61.000,48.000,39.000,38.000,40.000,36.000,37.000,27.000,43.000,36.000,32.000,41.000,45.000,38.000,34.000}
-63.326 LMS_LASER_2D_RIGHT LMS2 ID=4027,time=1225719874.974398,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=116,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.254,-1.000,15.841,12.890,11.028,9.918,9.008,8.196,7.386,6.790,6.315,5.877,5.502,5.184,4.818,4.572,4.283,4.082,3.859,3.655,3.483,3.336,3.198,3.050,2.940,2.763,2.634,2.577,2.524,2.432,2.335,2.273,2.210,2.140,2.078,2.019,1.963,1.910,1.838,1.804,1.743,1.707,1.681,1.645,1.593,1.578,1.554,1.518,1.482,1.449,1.432,1.404,1.377,1.342,1.324,1.305,1.295,1.265,1.249,1.225,1.216,1.200,1.190,1.193,1.192,1.210,1.223,1.218,1.209,1.186,1.149,1.140,1.146,1.138,1.135,1.131,1.116,1.113,1.088,1.077,1.058,1.058,1.054,1.053,1.057,1.044,1.037,1.022,1.013,1.000,1.007,0.997},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,18.000,0.000,111.000,115.000,85.000,65.000,59.000,56.000,55.000,61.000,67.000,67.000,68.000,70.000,71.000,72.000,73.000,74.000,73.000,77.000,77.000,79.000,77.000,79.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,77.000,79.000,80.000,77.000,78.000,78.000,73.000,73.000,72.000,74.000,76.000,76.000,76.000,74.000,73.000,72.000,70.000,64.000,67.000,70.000,70.000,72.000,76.000,76.000,71.000,62.000,52.000,50.000,57.000,62.000,70.000,70.000,65.000,60.000,62.000,60.000,57.000,48.000,34.000,39.000,34.000,33.000,31.000,32.000,41.000,48.000,37.000,46.000,53.000,54.000,47.000,38.000}
-63.331 DESIRED_THRUST iJoystick 85.5708487197
-63.331 DESIRED_RUDDER iJoystick 1.02847376934
-63.331 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.4713,19.6617,-0.9125},Vel=[3x1]{-0.9321,-0.7209,3.9744},Raw=[2x1]{21.6752,-0.9125},time=1225719874.97845697402954,Speed=1.17841184544844,Pitch=0.04038036720910,Roll=0.03589365974142,PitchDot=0.04038036720910,RollDot=0.00076274026951
-63.331 ODOMETRY_POSE iPlatform Pose=[3x1]{5.4713,19.6617,-0.9117},Vel=[3x1]{-0.9321,-0.7209,-2.3084},Raw=[2x1]{21.6752,-0.9125},time=1225719874.9785,Speed=1.1784,Pitch=-0.0037,Roll=0.0539,PitchDot=-0.0277,RollDot=0.0294
-63.310 LMS_LASER_2D_LEFT LMS1 ID=4153,time=1225719874.955526,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=150,Range=[181]{1.037,1.037,1.053,1.063,1.063,1.073,1.082,1.089,1.097,1.109,1.123,1.137,1.145,1.157,1.166,1.174,1.182,1.192,1.216,1.228,1.246,1.259,1.276,1.287,1.315,1.320,1.339,1.357,1.380,1.403,1.428,1.448,1.474,1.478,1.519,1.530,1.565,1.612,1.622,1.658,1.675,1.703,1.724,1.752,1.787,1.820,1.841,1.886,1.925,1.971,2.017,2.060,2.126,2.159,2.221,2.268,2.327,2.385,2.440,2.512,2.581,2.614,2.669,2.652,2.677,2.790,2.886,2.927,3.002,3.150,3.211,3.351,3.429,3.574,3.791,3.887,3.961,3.985,3.975,3.999,4.044,4.054,4.064,4.066,4.070,4.083,4.071,4.066,4.110,4.141,4.165,4.158,4.182,4.188,4.189,4.191,4.191,4.190,4.198,4.197,4.205,4.208,4.208,4.223,4.221,4.226,4.226,4.233,4.243,4.250,4.256,4.264,4.275,4.291,2.780,2.643,2.626,2.635,2.694,2.676,2.618,2.777,2.874,2.862,2.789,2.917,2.901,2.763,2.798,2.858,2.915,3.142,4.516,3.184,3.154,4.566,4.585,4.601,4.626,4.643,4.653,4.676,4.705,4.720,4.739,4.765,4.792,4.804,4.840,4.866,3.076,3.046,3.067,3.188,3.142,3.062,3.059,3.053,3.063,3.072,3.073,3.080,3.096,3.104,3.120,3.131,3.146,3.170,3.189,3.205,3.230,3.252,3.277,3.308,3.473,3.415,5.244,5.203,5.667,5.854,6.891},Reflectance=[181]{41.000,40.000,40.000,37.000,41.000,41.000,42.000,41.000,41.000,43.000,41.000,40.000,44.000,45.000,46.000,45.000,53.000,47.000,46.000,51.000,43.000,45.000,45.000,47.000,43.000,50.000,46.000,46.000,44.000,43.000,42.000,39.000,36.000,54.000,49.000,54.000,46.000,42.000,44.000,39.000,43.000,52.000,54.000,51.000,50.000,49.000,55.000,54.000,56.000,54.000,51.000,52.000,43.000,46.000,35.000,42.000,42.000,44.000,46.000,46.000,57.000,59.000,51.000,56.000,59.000,54.000,47.000,46.000,50.000,52.000,56.000,49.000,47.000,45.000,52.000,65.000,75.000,70.000,67.000,71.000,74.000,74.000,75.000,72.000,74.000,72.000,69.000,68.000,70.000,71.000,75.000,76.000,76.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,79.000,78.000,78.000,79.000,78.000,77.000,77.000,78.000,77.000,116.000,80.000,76.000,76.000,81.000,83.000,72.000,97.000,104.000,102.000,27.000,120.000,105.000,79.000,69.000,69.000,68.000,113.000,77.000,112.000,101.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,14.000,29.000,44.000,116.000,98.000,78.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,76.000,76.000,75.000,74.000,71.000,104.000,14.000,56.000,69.000,72.000,16.000,29.000}
-63.323 LMS_LASER_2D_LEFT LMS1 ID=4154,time=1225719874.968864,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=151,Range=[181]{1.037,1.041,1.049,1.064,1.062,1.066,1.084,1.090,1.098,1.111,1.121,1.137,1.139,1.158,1.169,1.178,1.185,1.201,1.214,1.230,1.243,1.268,1.276,1.289,1.303,1.322,1.348,1.358,1.380,1.403,1.434,1.437,1.485,1.496,1.537,1.534,1.572,1.617,1.635,1.664,1.689,1.698,1.716,1.763,1.802,1.823,1.854,1.895,1.927,1.956,2.018,2.048,2.135,2.173,2.226,2.278,2.340,2.388,2.460,2.510,2.593,2.665,2.670,2.663,2.699,2.833,2.900,2.942,3.040,3.167,3.229,3.373,3.464,3.598,3.783,3.922,3.961,3.984,3.989,4.016,4.048,4.063,4.073,4.066,4.075,4.081,4.065,4.082,4.113,4.154,4.166,4.156,4.183,4.188,4.181,4.191,4.191,4.191,4.199,4.196,4.208,4.208,4.208,4.222,4.227,4.225,4.234,4.234,4.244,4.250,4.258,4.260,4.277,4.283,2.723,2.626,2.617,2.637,2.721,2.681,2.739,2.863,2.863,2.885,4.403,3.078,2.866,2.809,2.886,2.903,2.923,3.138,4.530,3.100,4.548,4.567,4.585,4.609,4.624,4.644,4.661,4.688,4.706,4.733,4.748,4.773,4.791,3.065,3.056,3.154,3.126,3.104,3.035,3.034,3.036,3.038,3.048,3.047,3.055,3.063,3.072,3.089,3.094,3.113,3.122,3.138,3.162,3.187,3.194,3.228,3.254,3.285,3.301,3.356,5.265,5.247,5.211,5.239,5.337,6.858,6.904},Reflectance=[181]{41.000,43.000,42.000,45.000,46.000,47.000,43.000,41.000,45.000,44.000,44.000,44.000,46.000,41.000,48.000,51.000,51.000,47.000,46.000,49.000,47.000,45.000,45.000,48.000,46.000,47.000,46.000,51.000,49.000,48.000,38.000,32.000,37.000,47.000,46.000,59.000,53.000,40.000,41.000,37.000,46.000,54.000,54.000,51.000,49.000,55.000,55.000,55.000,62.000,59.000,59.000,54.000,38.000,44.000,44.000,35.000,44.000,42.000,42.000,50.000,50.000,53.000,51.000,56.000,56.000,50.000,49.000,49.000,51.000,48.000,49.000,46.000,51.000,49.000,53.000,63.000,70.000,69.000,71.000,74.000,75.000,74.000,75.000,72.000,72.000,72.000,70.000,70.000,71.000,72.000,76.000,75.000,76.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,115.000,80.000,76.000,74.000,88.000,76.000,77.000,110.000,103.000,107.000,79.000,117.000,97.000,72.000,74.000,72.000,68.000,103.000,79.000,28.000,79.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,21.000,46.000,115.000,107.000,94.000,78.000,77.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,77.000,78.000,78.000,78.000,77.000,76.000,76.000,75.000,75.000,74.000,64.000,32.000,65.000,63.000,61.000,74.000,4.000,30.000,27.000}
-63.334 LMS_LASER_2D_LEFT LMS1 ID=4155,time=1225719874.982200,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=152,Range=[181]{1.036,1.045,1.056,1.065,1.067,1.081,1.081,1.095,1.107,1.116,1.124,1.141,1.147,1.154,1.152,1.174,1.199,1.207,1.211,1.238,1.242,1.269,1.280,1.296,1.312,1.332,1.352,1.375,1.392,1.412,1.432,1.460,1.480,1.530,1.531,1.553,1.595,1.622,1.644,1.663,1.681,1.698,1.724,1.769,1.800,1.835,1.864,1.904,1.927,1.960,2.005,2.053,2.140,2.184,2.238,2.285,2.351,2.399,2.468,2.539,2.621,2.673,2.666,2.666,2.725,2.849,2.894,2.952,3.048,3.162,3.253,3.385,3.500,3.629,3.821,3.941,3.996,3.992,3.989,4.023,4.044,4.061,4.067,4.069,4.075,4.081,4.073,4.082,4.122,4.155,4.168,4.166,4.184,4.182,4.191,4.192,4.196,4.192,4.200,4.209,4.215,4.217,4.213,4.214,4.220,4.229,4.237,4.239,4.244,4.252,4.253,4.266,4.279,4.291,2.820,2.707,2.645,2.665,2.740,2.724,2.792,2.747,2.754,2.930,3.046,2.826,2.791,2.834,2.972,3.028,3.064,3.082,4.531,4.542,4.564,4.567,4.594,4.609,4.625,4.646,4.664,4.691,4.715,4.738,3.070,3.068,3.180,3.100,3.002,2.994,2.988,2.987,3.007,3.012,3.022,3.031,3.039,3.047,3.055,3.072,3.078,3.097,3.110,3.123,3.131,3.154,3.178,3.204,3.216,3.251,3.272,3.324,5.545,5.365,5.265,5.260,5.183,5.190,6.791,6.853,6.871},Reflectance=[181]{44.000,40.000,42.000,42.000,43.000,45.000,46.000,49.000,45.000,42.000,45.000,47.000,49.000,52.000,55.000,50.000,46.000,46.000,48.000,44.000,46.000,47.000,43.000,47.000,46.000,47.000,48.000,45.000,45.000,48.000,44.000,37.000,42.000,37.000,54.000,52.000,43.000,38.000,45.000,45.000,51.000,54.000,54.000,54.000,48.000,52.000,52.000,55.000,64.000,56.000,62.000,52.000,46.000,45.000,45.000,42.000,46.000,47.000,45.000,45.000,47.000,53.000,54.000,58.000,56.000,50.000,50.000,46.000,54.000,54.000,48.000,48.000,45.000,47.000,54.000,69.000,75.000,74.000,71.000,73.000,74.000,76.000,75.000,73.000,72.000,72.000,70.000,70.000,71.000,72.000,76.000,76.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,122.000,93.000,74.000,75.000,88.000,78.000,94.000,81.000,76.000,116.000,118.000,87.000,74.000,72.000,79.000,94.000,91.000,30.000,79.000,79.000,80.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,26.000,44.000,116.000,92.000,76.000,76.000,74.000,72.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,79.000,78.000,77.000,76.000,76.000,75.000,74.000,68.000,52.000,59.000,65.000,66.000,67.000,66.000,44.000,32.000,33.000,30.000}
-63.339 LMS_LASER_2D_RIGHT LMS2 ID=4028,time=1225719874.987734,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=117,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.990,18.260,15.289,12.678,10.833,9.722,8.899,8.043,7.286,6.729,6.209,5.794,5.450,5.120,4.792,4.519,4.247,4.008,3.812,3.632,3.456,3.316,3.178,3.033,2.890,2.760,2.639,2.578,2.513,2.411,2.327,2.256,2.192,2.114,2.054,1.994,1.937,1.901,1.829,1.795,1.741,1.699,1.660,1.637,1.579,1.566,1.536,1.509,1.470,1.439,1.425,1.407,1.374,1.344,1.325,1.303,1.279,1.261,1.250,1.233,1.209,1.192,1.186,1.186,1.182,1.207,1.225,1.213,1.196,1.149,1.141,1.147,1.154,1.146,1.133,1.129,1.117,1.118,1.101,1.071,1.050,1.031,1.025,1.063,1.039,1.048,1.028,1.007,1.008,1.012,1.006,0.986},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,55.000,21.000,125.000,106.000,83.000,65.000,57.000,57.000,56.000,61.000,68.000,67.000,67.000,70.000,71.000,72.000,72.000,74.000,75.000,78.000,77.000,78.000,79.000,79.000,80.000,80.000,79.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,78.000,77.000,78.000,77.000,77.000,74.000,65.000,71.000,77.000,77.000,75.000,74.000,74.000,75.000,71.000,72.000,68.000,68.000,71.000,76.000,77.000,77.000,70.000,60.000,45.000,51.000,64.000,69.000,71.000,66.000,59.000,60.000,61.000,60.000,57.000,51.000,41.000,34.000,31.000,27.000,26.000,37.000,53.000,42.000,52.000,58.000,58.000,48.000,41.000,33.000}
-63.355 DESIRED_THRUST iJoystick 85.5708487197
-63.355 DESIRED_RUDDER iJoystick 1.02847376934
-63.346 LMS_LASER_2D_LEFT LMS1 ID=4156,time=1225719874.995535,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=153,Range=[181]{1.047,1.051,1.059,1.072,1.067,1.079,1.085,1.103,1.107,1.119,1.123,1.111,1.141,1.150,1.151,1.179,1.200,1.219,1.227,1.247,1.262,1.274,1.290,1.308,1.317,1.339,1.362,1.380,1.394,1.410,1.439,1.460,1.487,1.519,1.539,1.569,1.584,1.624,1.643,1.669,1.688,1.706,1.734,1.768,1.803,1.823,1.878,1.915,1.930,1.970,2.016,2.060,2.149,2.195,2.240,2.307,2.355,2.411,2.480,2.549,2.637,2.669,2.671,2.669,2.746,2.868,2.913,2.966,3.051,3.164,3.262,3.371,3.547,3.687,3.868,3.963,3.991,3.988,3.998,4.023,4.062,4.061,4.069,4.073,4.078,4.096,4.069,4.090,4.129,4.161,4.167,4.174,4.190,4.183,4.184,4.197,4.192,4.196,4.199,4.208,4.214,4.217,4.218,4.223,4.220,4.231,4.239,4.240,4.250,4.255,4.257,4.270,4.284,4.287,2.819,2.707,2.708,2.787,2.805,2.907,2.880,2.728,2.788,2.946,2.880,2.751,2.788,2.854,3.041,3.094,3.026,4.512,4.537,4.548,4.568,4.581,4.600,4.612,4.637,4.646,4.672,3.114,3.244,3.153,3.098,3.030,3.019,2.991,2.961,2.966,2.968,2.979,2.991,3.003,3.023,3.027,3.050,3.058,3.063,3.072,3.092,3.102,3.114,3.129,3.143,3.177,3.193,3.224,3.343,3.284,3.336,5.489,5.565,5.450,5.368,5.245,5.229,5.186,6.780,6.838,5.897},Reflectance=[181]{45.000,39.000,38.000,41.000,43.000,46.000,43.000,44.000,42.000,43.000,53.000,56.000,54.000,54.000,55.000,49.000,47.000,43.000,43.000,44.000,43.000,44.000,39.000,40.000,44.000,46.000,44.000,44.000,43.000,47.000,48.000,46.000,42.000,46.000,46.000,52.000,51.000,40.000,46.000,46.000,54.000,57.000,55.000,54.000,49.000,55.000,51.000,55.000,67.000,58.000,59.000,52.000,41.000,42.000,34.000,40.000,43.000,48.000,43.000,47.000,44.000,51.000,52.000,59.000,50.000,46.000,48.000,49.000,55.000,47.000,48.000,50.000,45.000,44.000,56.000,73.000,76.000,73.000,73.000,73.000,77.000,76.000,76.000,75.000,73.000,74.000,69.000,69.000,70.000,74.000,76.000,76.000,78.000,78.000,79.000,80.000,79.000,79.000,79.000,79.000,80.000,79.000,80.000,80.000,79.000,79.000,79.000,80.000,80.000,79.000,79.000,80.000,80.000,79.000,118.000,82.000,81.000,88.000,88.000,110.000,118.000,77.000,82.000,107.000,109.000,71.000,73.000,72.000,72.000,90.000,31.000,79.000,80.000,80.000,80.000,79.000,80.000,79.000,78.000,78.000,78.000,16.000,121.000,108.000,88.000,79.000,75.000,75.000,76.000,78.000,76.000,74.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,77.000,78.000,78.000,77.000,76.000,75.000,74.000,97.000,58.000,19.000,62.000,59.000,68.000,70.000,60.000,63.000,35.000,32.000,33.000,13.000}
-63.350 LMS_LASER_2D_RIGHT LMS2 ID=4029,time=1225719875.001068,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=118,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.866,18.215,15.013,12.493,10.712,9.611,8.788,7.928,7.218,6.669,6.156,5.742,5.433,5.076,4.774,4.466,4.221,3.990,3.763,3.584,3.410,3.274,3.144,2.999,2.856,2.740,2.652,2.579,2.482,2.371,2.307,2.247,2.184,2.114,2.053,1.985,1.935,1.882,1.829,1.776,1.733,1.698,1.665,1.607,1.553,1.553,1.544,1.516,1.469,1.451,1.426,1.402,1.369,1.346,1.315,1.289,1.264,1.243,1.233,1.209,1.201,1.195,1.182,1.177,1.189,1.196,1.222,1.217,1.187,1.149,1.148,1.162,1.158,1.150,1.139,1.135,1.132,1.115,1.096,1.060,1.052,1.061,1.036,1.057,1.039,1.022,1.011,1.011,1.017,1.011,1.001,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,61.000,26.000,119.000,100.000,81.000,64.000,56.000,58.000,56.000,63.000,69.000,68.000,68.000,70.000,70.000,73.000,72.000,74.000,75.000,77.000,76.000,79.000,80.000,80.000,80.000,80.000,80.000,81.000,79.000,77.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,77.000,73.000,72.000,72.000,76.000,69.000,64.000,77.000,77.000,75.000,73.000,75.000,74.000,73.000,74.000,71.000,68.000,72.000,73.000,77.000,76.000,74.000,67.000,59.000,43.000,37.000,55.000,70.000,68.000,63.000,57.000,53.000,60.000,54.000,53.000,49.000,45.000,36.000,35.000,37.000,28.000,34.000,49.000,52.000,59.000,56.000,47.000,39.000,36.000,34.000}
-63.358 LMS_LASER_2D_LEFT LMS1 ID=4157,time=1225719875.008869,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=154,Range=[181]{1.044,1.047,1.056,1.066,1.070,1.076,1.090,1.089,1.116,1.115,1.129,1.123,1.140,1.148,1.150,1.182,1.208,1.218,1.236,1.255,1.263,1.278,1.286,1.311,1.326,1.353,1.360,1.377,1.394,1.414,1.436,1.464,1.465,1.486,1.550,1.561,1.582,1.606,1.631,1.663,1.691,1.709,1.747,1.773,1.809,1.838,1.886,1.921,1.963,1.991,2.047,2.068,2.150,2.204,2.256,2.308,2.362,2.418,2.487,2.566,2.644,2.668,2.671,2.669,2.754,2.859,2.932,2.984,3.085,3.168,3.297,3.409,3.551,3.723,3.901,3.967,3.985,3.990,3.987,4.023,4.053,4.066,4.064,4.067,4.073,4.086,4.063,4.085,4.131,4.161,4.158,4.165,4.187,4.182,4.183,4.182,4.194,4.191,4.196,4.203,4.211,4.216,4.218,4.211,4.220,4.225,4.235,4.241,4.235,4.252,4.253,4.260,4.272,2.872,2.702,2.704,2.713,2.789,2.900,2.713,2.863,2.787,2.876,2.963,2.806,2.773,2.812,2.921,3.000,3.162,4.494,4.515,4.530,4.544,4.558,4.576,4.594,4.618,3.170,3.306,3.208,3.085,3.044,3.027,3.020,3.002,2.978,2.961,2.962,2.961,2.964,2.977,2.983,3.000,3.021,3.028,3.045,3.054,3.072,3.078,3.102,3.107,3.126,3.147,3.171,3.191,3.316,3.257,3.294,5.524,5.519,5.485,5.594,6.532,5.321,5.250,5.183,6.749,6.796,6.866,6.891},Reflectance=[181]{44.000,45.000,42.000,42.000,40.000,48.000,45.000,46.000,42.000,41.000,49.000,53.000,53.000,61.000,54.000,45.000,45.000,38.000,43.000,39.000,39.000,47.000,46.000,45.000,44.000,39.000,43.000,47.000,51.000,49.000,47.000,48.000,59.000,54.000,43.000,52.000,58.000,53.000,49.000,46.000,51.000,55.000,52.000,52.000,52.000,50.000,54.000,55.000,47.000,55.000,54.000,55.000,45.000,42.000,44.000,41.000,47.000,48.000,42.000,42.000,43.000,51.000,52.000,55.000,50.000,50.000,49.000,46.000,48.000,49.000,48.000,46.000,52.000,45.000,59.000,74.000,75.000,74.000,70.000,71.000,74.000,75.000,75.000,73.000,72.000,73.000,69.000,68.000,71.000,74.000,76.000,75.000,77.000,78.000,79.000,78.000,79.000,79.000,78.000,77.000,79.000,78.000,79.000,79.000,79.000,78.000,79.000,80.000,79.000,78.000,79.000,79.000,79.000,119.000,77.000,75.000,75.000,86.000,112.000,26.000,110.000,83.000,106.000,114.000,80.000,74.000,70.000,75.000,75.000,108.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,13.000,119.000,110.000,81.000,78.000,78.000,78.000,76.000,74.000,76.000,77.000,79.000,70.000,57.000,75.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,75.000,74.000,72.000,95.000,62.000,29.000,57.000,59.000,59.000,56.000,30.000,29.000,58.000,36.000,29.000,30.000,32.000,31.000}
-63.362 LMS_LASER_2D_RIGHT LMS2 ID=4030,time=1225719875.014400,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=119,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.723,17.264,14.683,12.364,10.626,9.539,8.736,7.830,7.170,6.634,6.120,5.724,5.407,5.049,4.757,4.412,4.211,3.976,3.796,3.575,3.412,3.255,3.131,2.987,2.834,2.742,2.655,2.560,2.473,2.373,2.300,2.238,2.174,2.115,2.054,1.977,1.935,1.882,1.830,1.776,1.735,1.698,1.670,1.605,1.570,1.565,1.536,1.498,1.456,1.438,1.428,1.396,1.374,1.342,1.322,1.290,1.262,1.243,1.235,1.210,1.210,1.193,1.186,1.184,1.190,1.199,1.214,1.223,1.199,1.155,1.155,1.163,1.151,1.150,1.135,1.132,1.121,1.106,1.093,1.058,1.053,1.065,1.056,1.038,1.029,1.023,1.020,1.021,1.025,1.005,0.998,0.987},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,32.000,11.000,115.000,99.000,79.000,63.000,57.000,59.000,58.000,64.000,70.000,67.000,67.000,69.000,71.000,74.000,72.000,75.000,75.000,77.000,77.000,79.000,80.000,79.000,81.000,81.000,81.000,80.000,79.000,78.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,76.000,70.000,72.000,74.000,76.000,69.000,72.000,78.000,78.000,77.000,75.000,73.000,71.000,74.000,74.000,72.000,72.000,74.000,76.000,76.000,77.000,74.000,67.000,60.000,48.000,39.000,52.000,66.000,67.000,64.000,58.000,53.000,54.000,53.000,52.000,52.000,41.000,34.000,37.000,38.000,40.000,49.000,56.000,57.000,56.000,52.000,43.000,40.000,34.000,32.000}
-63.367 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.5081,19.6900,-0.9148},Vel=[3x1]{-0.9326,-0.7179,8.5897},Raw=[2x1]{21.7216,-0.9148},time=1225719875.01446104049683,Speed=1.17695160772174,Pitch=0.04262372094293,Roll=0.03813701347526,PitchDot=0.03589365974142,RollDot=0.00100950918023
-63.367 ODOMETRY_POSE iPlatform Pose=[3x1]{5.5081,19.6900,-0.9139},Vel=[3x1]{-0.9326,-0.7179,2.3062},Raw=[2x1]{21.7216,-0.9148},time=1225719875.0145,Speed=1.1770,Pitch=-0.0042,Roll=0.0570,PitchDot=-0.0233,RollDot=-0.0273
-63.371 LMS_LASER_2D_LEFT LMS1 ID=4158,time=1225719875.022202,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=155,Range=[181]{1.039,1.050,1.058,1.071,1.080,1.085,1.091,1.093,1.112,1.123,1.132,1.143,1.139,1.140,1.131,1.182,1.212,1.221,1.237,1.247,1.265,1.289,1.292,1.315,1.324,1.342,1.356,1.376,1.391,1.417,1.434,1.445,1.441,1.487,1.550,1.577,1.599,1.626,1.627,1.657,1.699,1.718,1.734,1.767,1.812,1.852,1.883,1.929,1.956,2.005,2.052,2.093,2.150,2.206,2.254,2.310,2.357,2.430,2.492,2.565,2.649,2.674,2.668,2.683,2.763,2.880,2.941,2.998,3.080,3.190,3.307,3.440,3.577,3.736,3.898,3.972,3.986,3.980,3.992,4.029,4.054,4.055,4.076,4.064,4.076,4.084,4.060,4.086,4.134,4.162,4.158,4.165,4.183,4.179,4.183,4.182,4.184,4.191,4.199,4.203,4.208,4.207,4.208,4.211,4.222,4.226,4.229,4.237,4.243,4.253,4.253,4.259,4.278,2.797,2.678,2.682,2.696,2.797,2.730,2.800,2.717,2.792,2.819,2.835,2.832,2.811,2.879,2.915,3.005,3.191,4.493,4.511,4.521,4.542,4.549,3.180,3.328,3.240,3.120,3.073,3.052,3.038,3.030,3.008,2.997,2.975,2.967,2.955,2.949,2.963,2.963,2.968,2.976,2.989,3.016,3.035,3.044,3.058,3.073,3.098,3.114,3.129,3.153,3.254,3.302,3.250,3.271,5.445,5.436,5.521,5.517,5.483,5.586,6.555,5.324,5.222,5.159,6.778,6.826,6.877,6.919},Reflectance=[181]{42.000,43.000,43.000,41.000,41.000,43.000,42.000,48.000,44.000,45.000,46.000,43.000,53.000,61.000,66.000,45.000,40.000,40.000,38.000,35.000,36.000,39.000,40.000,43.000,43.000,48.000,50.000,51.000,49.000,50.000,50.000,59.000,66.000,54.000,43.000,43.000,45.000,45.000,55.000,48.000,46.000,55.000,55.000,53.000,50.000,51.000,53.000,54.000,55.000,50.000,52.000,48.000,45.000,43.000,37.000,42.000,44.000,40.000,44.000,45.000,46.000,50.000,51.000,53.000,49.000,48.000,49.000,48.000,50.000,45.000,48.000,48.000,55.000,47.000,58.000,76.000,72.000,68.000,72.000,72.000,74.000,75.000,75.000,75.000,73.000,73.000,68.000,68.000,72.000,75.000,76.000,75.000,76.000,77.000,79.000,78.000,79.000,79.000,79.000,77.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,107.000,75.000,77.000,76.000,100.000,34.000,102.000,69.000,81.000,79.000,75.000,79.000,72.000,75.000,75.000,86.000,26.000,78.000,78.000,79.000,79.000,79.000,31.000,114.000,100.000,78.000,77.000,78.000,79.000,78.000,78.000,77.000,78.000,78.000,72.000,70.000,74.000,72.000,62.000,71.000,77.000,77.000,78.000,78.000,77.000,77.000,76.000,76.000,75.000,74.000,91.000,100.000,54.000,30.000,65.000,66.000,56.000,54.000,58.000,54.000,28.000,31.000,31.000,34.000,29.000,31.000,32.000,30.000}
-63.379 DESIRED_THRUST iJoystick 86.60237434
-63.379 DESIRED_RUDDER iJoystick 0
-63.387 LMS_LASER_2D_RIGHT LMS2 ID=4031,time=1225719875.027744,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=120,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.813,17.158,14.524,12.215,10.560,9.511,8.697,7.786,7.155,6.615,6.100,5.724,5.398,5.024,4.748,4.395,4.202,3.947,3.791,3.575,3.413,3.253,3.122,2.984,2.817,2.734,2.634,2.552,2.435,2.377,2.301,2.228,2.157,2.106,2.053,1.977,1.935,1.884,1.830,1.776,1.733,1.707,1.679,1.622,1.602,1.578,1.537,1.491,1.470,1.436,1.409,1.399,1.373,1.359,1.322,1.291,1.273,1.253,1.228,1.219,1.203,1.196,1.185,1.179,1.182,1.197,1.216,1.213,1.211,1.180,1.164,1.166,1.155,1.156,1.137,1.123,1.115,1.099,1.082,1.061,1.048,1.066,1.063,1.039,1.040,1.036,1.037,1.027,1.012,1.007,1.001,0.984},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,38.000,14.000,117.000,99.000,78.000,62.000,56.000,59.000,60.000,63.000,70.000,67.000,68.000,70.000,70.000,74.000,71.000,74.000,76.000,77.000,77.000,78.000,80.000,78.000,82.000,81.000,80.000,81.000,81.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,79.000,75.000,78.000,78.000,77.000,72.000,78.000,78.000,78.000,77.000,75.000,71.000,69.000,74.000,74.000,72.000,74.000,77.000,77.000,77.000,77.000,75.000,70.000,59.000,49.000,43.000,43.000,60.000,67.000,61.000,56.000,52.000,51.000,57.000,49.000,53.000,50.000,37.000,38.000,43.000,48.000,57.000,53.000,40.000,40.000,39.000,45.000,38.000,36.000,35.000}
-63.398 LMS_LASER_2D_RIGHT LMS2 ID=4032,time=1225719875.041085,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=121,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.773,17.620,14.485,12.248,10.586,9.512,8.706,7.796,7.155,6.615,6.091,5.716,5.380,5.007,4.748,4.385,4.194,3.972,3.803,3.593,3.400,3.248,3.131,2.986,2.809,2.719,2.636,2.533,2.455,2.362,2.298,2.227,2.157,2.106,2.053,1.977,1.944,1.884,1.839,1.785,1.739,1.711,1.679,1.649,1.604,1.576,1.539,1.500,1.469,1.437,1.420,1.409,1.378,1.350,1.313,1.283,1.275,1.253,1.236,1.218,1.205,1.199,1.184,1.176,1.175,1.190,1.195,1.205,1.207,1.192,1.178,1.172,1.160,1.156,1.140,1.124,1.125,1.115,1.092,1.052,1.046,1.052,1.064,1.057,1.016,1.001,1.024,1.028,1.013,1.010,1.001,0.998},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,45.000,55.000,121.000,98.000,78.000,62.000,56.000,59.000,59.000,63.000,70.000,68.000,68.000,70.000,70.000,73.000,72.000,74.000,75.000,76.000,77.000,79.000,80.000,78.000,81.000,82.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,77.000,76.000,77.000,78.000,78.000,78.000,77.000,71.000,70.000,75.000,75.000,73.000,74.000,76.000,77.000,78.000,78.000,76.000,72.000,60.000,58.000,51.000,48.000,57.000,64.000,60.000,54.000,52.000,53.000,53.000,47.000,49.000,43.000,37.000,37.000,37.000,40.000,41.000,28.000,27.000,33.000,37.000,40.000,42.000,36.000,38.000}
-63.403 DESIRED_THRUST iJoystick 86.60237434
-63.403 DESIRED_RUDDER iJoystick 0
-63.403 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.5357,19.7113,-0.9171},Vel=[3x1]{-0.9367,-0.7175,6.0256},Raw=[2x1]{21.7565,-0.9171},time=1225719875.05049800872803,Speed=1.17987208317514,Pitch=0.04262372094293,Roll=0.04038036720910,PitchDot=0.04486707467677,RollDot=0.00029163598540
-63.403 ODOMETRY_POSE iPlatform Pose=[3x1]{5.5357,19.7113,-0.9161},Vel=[3x1]{-0.9367,-0.7175,-0.2578},Raw=[2x1]{21.7565,-0.9171},time=1225719875.0505,Speed=1.1799,Pitch=-0.0061,Roll=0.0584,PitchDot=0.0433,RollDot=0.0117
-63.411 LMS_LASER_2D_RIGHT LMS2 ID=4033,time=1225719875.054426,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=122,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.788,18.221,14.713,12.354,10.620,9.555,8.742,7.849,7.180,6.634,6.120,5.733,5.407,5.016,4.748,4.422,4.193,3.981,3.813,3.592,3.400,3.254,3.128,2.985,2.818,2.734,2.631,2.533,2.468,2.384,2.300,2.227,2.158,2.104,2.044,1.993,1.944,1.892,1.847,1.787,1.754,1.693,1.669,1.642,1.592,1.567,1.531,1.503,1.458,1.436,1.420,1.400,1.377,1.351,1.331,1.298,1.272,1.252,1.234,1.213,1.205,1.193,1.192,1.181,1.175,1.187,1.193,1.213,1.208,1.188,1.179,1.170,1.166,1.164,1.138,1.127,1.132,1.103,1.093,1.061,1.054,1.052,1.069,1.064,1.031,1.002,1.022,1.024,0.995,0.962,0.966,1.001},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,43.000,31.000,120.000,98.000,80.000,62.000,56.000,59.000,58.000,63.000,69.000,68.000,68.000,70.000,70.000,73.000,71.000,73.000,75.000,76.000,77.000,78.000,78.000,78.000,82.000,81.000,80.000,81.000,80.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,77.000,78.000,75.000,78.000,79.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,76.000,73.000,71.000,74.000,74.000,71.000,70.000,75.000,77.000,79.000,78.000,78.000,72.000,64.000,58.000,48.000,49.000,59.000,65.000,63.000,57.000,52.000,56.000,54.000,46.000,51.000,44.000,37.000,40.000,39.000,39.000,46.000,30.000,26.000,32.000,34.000,31.000,25.000,26.000,41.000}
-63.382 LMS_LASER_2D_LEFT LMS1 ID=4159,time=1225719875.035533,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=156,Range=[181]{1.044,1.049,1.057,1.067,1.069,1.079,1.089,1.112,1.114,1.128,1.139,1.149,1.146,1.145,1.165,1.191,1.210,1.229,1.245,1.249,1.267,1.281,1.297,1.315,1.331,1.348,1.370,1.376,1.398,1.415,1.443,1.442,1.457,1.505,1.548,1.575,1.595,1.617,1.627,1.669,1.699,1.710,1.741,1.778,1.814,1.844,1.886,1.928,1.965,2.005,2.064,2.095,2.154,2.203,2.258,2.310,2.373,2.438,2.502,2.571,2.647,2.667,2.665,2.693,2.766,2.866,2.926,3.002,3.086,3.171,3.276,3.448,3.596,3.723,3.916,3.976,3.981,3.974,3.991,4.019,4.058,4.064,4.059,4.059,4.067,4.081,4.064,4.086,4.124,4.164,4.159,4.167,4.181,4.184,4.174,4.183,4.186,4.190,4.200,4.203,4.206,4.208,4.204,4.220,4.211,4.226,4.226,4.234,4.243,4.243,4.252,4.260,2.707,2.722,2.671,2.691,2.766,2.752,2.763,2.729,2.760,2.894,2.987,3.150,2.972,2.878,2.911,2.916,2.949,3.335,3.506,3.481,3.378,3.298,3.189,3.134,3.111,3.095,3.070,3.055,3.042,3.028,3.015,3.004,2.978,2.969,2.968,2.963,2.935,2.967,2.956,2.960,2.963,2.986,3.029,3.041,3.055,3.079,3.095,3.118,3.223,3.264,3.205,3.225,5.335,5.367,5.419,5.445,5.437,5.517,5.517,5.483,5.578,6.554,6.593,5.175,5.147,6.779,6.818,6.881,6.961},Reflectance=[181]{44.000,42.000,38.000,43.000,44.000,46.000,46.000,40.000,41.000,44.000,41.000,42.000,49.000,56.000,53.000,46.000,43.000,40.000,38.000,37.000,41.000,38.000,36.000,43.000,42.000,45.000,43.000,51.000,52.000,49.000,50.000,57.000,56.000,54.000,46.000,42.000,48.000,54.000,55.000,53.000,54.000,55.000,54.000,54.000,54.000,52.000,51.000,50.000,48.000,50.000,45.000,49.000,39.000,46.000,45.000,42.000,43.000,41.000,45.000,44.000,50.000,50.000,49.000,45.000,47.000,53.000,50.000,46.000,52.000,46.000,50.000,47.000,60.000,49.000,59.000,75.000,73.000,69.000,71.000,70.000,75.000,77.000,76.000,76.000,73.000,72.000,69.000,68.000,71.000,75.000,76.000,76.000,76.000,77.000,78.000,79.000,79.000,78.000,79.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,35.000,85.000,76.000,77.000,87.000,76.000,79.000,75.000,76.000,89.000,112.000,106.000,100.000,74.000,72.000,75.000,79.000,105.000,110.000,110.000,112.000,104.000,79.000,74.000,75.000,78.000,78.000,78.000,77.000,76.000,74.000,74.000,78.000,79.000,76.000,74.000,63.000,73.000,77.000,76.000,77.000,76.000,76.000,77.000,76.000,76.000,75.000,75.000,93.000,97.000,57.000,33.000,68.000,67.000,61.000,65.000,65.000,54.000,54.000,58.000,50.000,27.000,31.000,37.000,30.000,28.000,34.000,32.000,29.000}
-63.411 LMS_LASER_2D_LEFT LMS1 ID=4160,time=1225719875.048879,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=157,Range=[181]{1.048,1.047,1.053,1.069,1.073,1.089,1.098,1.103,1.118,1.132,1.136,1.152,1.164,1.172,1.179,1.200,1.207,1.227,1.232,1.249,1.263,1.283,1.299,1.307,1.329,1.343,1.359,1.374,1.397,1.410,1.440,1.466,1.495,1.513,1.546,1.584,1.602,1.623,1.623,1.662,1.699,1.717,1.742,1.776,1.805,1.854,1.878,1.919,1.969,2.016,2.056,2.098,2.152,2.196,2.239,2.301,2.365,2.437,2.495,2.566,2.639,2.674,2.666,2.694,2.776,2.853,2.931,3.007,3.088,3.199,3.267,3.423,3.592,3.687,3.911,3.967,3.980,3.983,3.985,4.017,4.048,4.052,4.062,4.059,4.069,4.080,4.058,4.085,4.136,4.152,4.160,4.157,4.184,4.178,4.183,4.181,4.188,4.198,4.199,4.198,4.198,4.200,4.199,4.206,4.218,4.218,4.226,4.235,4.241,4.243,4.252,4.261,4.270,2.855,2.817,2.726,2.940,2.805,2.769,2.797,2.796,2.906,3.368,3.046,3.030,2.989,2.902,2.933,2.936,3.120,3.195,3.175,3.150,3.133,3.118,3.096,3.078,3.069,3.058,3.042,3.021,3.014,2.996,2.988,2.969,2.984,2.968,2.966,2.962,2.964,2.962,2.962,2.966,2.997,3.041,3.065,3.090,3.171,3.228,3.176,3.198,5.238,5.256,5.286,5.321,5.365,5.414,5.445,5.454,5.510,5.513,5.482,5.565,6.536,6.604,5.213,6.688,6.786,6.835,6.882,6.949},Reflectance=[181]{38.000,46.000,44.000,44.000,46.000,45.000,41.000,44.000,43.000,42.000,36.000,35.000,40.000,46.000,44.000,42.000,45.000,43.000,45.000,41.000,43.000,40.000,40.000,43.000,45.000,48.000,47.000,50.000,52.000,51.000,49.000,49.000,45.000,46.000,40.000,42.000,42.000,53.000,57.000,54.000,54.000,54.000,54.000,53.000,54.000,52.000,55.000,54.000,46.000,48.000,46.000,46.000,42.000,55.000,54.000,47.000,48.000,48.000,46.000,45.000,54.000,50.000,50.000,47.000,48.000,47.000,48.000,49.000,49.000,45.000,46.000,49.000,58.000,60.000,60.000,74.000,73.000,69.000,70.000,69.000,75.000,76.000,77.000,76.000,73.000,72.000,70.000,68.000,72.000,74.000,77.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,119.000,109.000,38.000,117.000,85.000,76.000,76.000,76.000,102.000,104.000,83.000,78.000,79.000,71.000,73.000,79.000,79.000,76.000,75.000,76.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,77.000,77.000,79.000,73.000,69.000,75.000,69.000,70.000,58.000,74.000,75.000,75.000,75.000,74.000,74.000,87.000,97.000,52.000,28.000,64.000,66.000,67.000,67.000,63.000,59.000,64.000,61.000,55.000,59.000,58.000,52.000,22.000,29.000,45.000,25.000,29.000,29.000,31.000,28.000}
-63.422 LMS_LASER_2D_RIGHT LMS2 ID=4034,time=1225719875.067765,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=123,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.790,18.110,15.027,12.546,10.743,9.639,8.817,7.947,7.227,6.678,6.147,5.768,5.441,5.050,4.782,4.439,4.211,3.999,3.814,3.599,3.413,3.269,3.135,2.998,2.827,2.743,2.644,2.552,2.496,2.389,2.307,2.237,2.158,2.106,2.053,1.993,1.935,1.892,1.832,1.775,1.740,1.701,1.669,1.642,1.596,1.570,1.539,1.501,1.469,1.446,1.427,1.407,1.379,1.355,1.333,1.306,1.281,1.262,1.243,1.220,1.201,1.198,1.182,1.178,1.174,1.188,1.197,1.212,1.210,1.201,1.191,1.176,1.172,1.151,1.133,1.126,1.136,1.114,1.089,1.066,1.056,1.052,1.056,1.030,1.034,1.006,1.020,1.023,1.006,0.965,0.959,0.974},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,38.000,26.000,125.000,99.000,82.000,63.000,57.000,58.000,56.000,63.000,69.000,68.000,68.000,70.000,69.000,73.000,72.000,72.000,75.000,76.000,77.000,78.000,78.000,77.000,82.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,77.000,78.000,79.000,78.000,78.000,77.000,76.000,77.000,78.000,78.000,77.000,77.000,75.000,73.000,73.000,74.000,73.000,71.000,74.000,76.000,78.000,78.000,77.000,70.000,64.000,56.000,38.000,40.000,50.000,57.000,62.000,60.000,58.000,61.000,62.000,48.000,45.000,45.000,38.000,40.000,39.000,34.000,29.000,30.000,26.000,30.000,34.000,30.000,26.000,26.000,30.000}
-63.427 DESIRED_THRUST iJoystick 86.60237434
-63.427 DESIRED_RUDDER iJoystick 0
-63.439 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.5719,19.7388,-0.9219},Vel=[3x1]{-0.9180,-0.6962,11.2821},Raw=[2x1]{21.8019,-0.9219},time=1225719875.08648490905762,Speed=1.15212756636780,Pitch=0.04486707467677,Roll=0.04038036720910,PitchDot=0.02467689107222,RollDot=-0.00040380367209
-63.439 ODOMETRY_POSE iPlatform Pose=[3x1]{5.5719,19.7388,-0.9208},Vel=[3x1]{-0.9180,-0.6962,-1.2844},Raw=[2x1]{21.8019,-0.9219},time=1225719875.0865,Speed=1.1521,Pitch=-0.0050,Roll=0.0601,PitchDot=0.0074,RollDot=0.0236
-62.637 CAMERA_FILE_WRITE iCameraLadybug time=1225719874.284,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.284-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.284-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.284-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.284-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.284-4.jpg
-63.422 LMS_LASER_2D_LEFT LMS1 ID=4161,time=1225719875.062223,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=158,Range=[181]{1.040,1.048,1.059,1.073,1.078,1.084,1.098,1.107,1.115,1.123,1.141,1.141,1.157,1.173,1.190,1.193,1.199,1.220,1.233,1.247,1.271,1.275,1.297,1.311,1.329,1.337,1.355,1.378,1.394,1.408,1.431,1.460,1.487,1.518,1.547,1.577,1.601,1.610,1.614,1.662,1.699,1.711,1.741,1.768,1.806,1.841,1.881,1.928,1.966,2.009,2.057,2.103,2.152,2.206,2.258,2.307,2.361,2.403,2.484,2.552,2.634,2.662,2.662,2.681,2.773,2.849,2.927,2.996,3.066,3.206,3.258,3.377,3.599,3.706,3.854,3.963,3.986,3.973,3.980,4.019,4.036,4.052,4.052,4.058,4.061,4.063,4.055,4.083,4.123,4.152,4.149,4.156,4.176,4.173,4.174,4.182,4.182,4.189,4.190,4.191,4.195,4.200,4.199,4.209,4.218,4.220,4.226,4.234,4.233,4.242,4.252,4.260,4.268,4.278,4.284,2.871,2.896,2.794,2.812,2.773,2.772,2.870,3.023,2.935,2.933,2.896,2.918,2.957,2.984,3.162,3.159,3.149,3.132,3.115,3.101,3.087,3.069,3.056,3.046,3.029,3.018,3.006,2.999,2.988,2.982,2.980,2.979,2.978,2.966,2.967,2.961,2.965,2.989,3.048,3.081,3.190,3.252,3.168,5.115,5.141,5.181,5.213,5.247,5.275,5.318,5.365,5.405,5.445,5.446,5.505,5.518,5.483,5.543,5.940,6.593,5.201,6.671,6.778,6.819,6.882,6.938},Reflectance=[181]{36.000,42.000,43.000,42.000,44.000,43.000,41.000,45.000,45.000,45.000,42.000,47.000,45.000,45.000,45.000,43.000,46.000,39.000,45.000,44.000,43.000,46.000,43.000,45.000,45.000,50.000,46.000,48.000,51.000,46.000,49.000,46.000,45.000,44.000,45.000,43.000,41.000,55.000,63.000,54.000,54.000,55.000,54.000,54.000,55.000,51.000,52.000,46.000,48.000,44.000,47.000,49.000,47.000,43.000,42.000,35.000,50.000,49.000,49.000,56.000,48.000,52.000,52.000,56.000,54.000,46.000,46.000,55.000,51.000,45.000,45.000,44.000,49.000,57.000,62.000,76.000,72.000,69.000,71.000,72.000,75.000,76.000,76.000,75.000,74.000,69.000,72.000,70.000,71.000,74.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,31.000,101.000,75.000,75.000,74.000,74.000,79.000,80.000,76.000,75.000,75.000,71.000,75.000,82.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,75.000,69.000,76.000,78.000,79.000,75.000,75.000,74.000,68.000,70.000,74.000,76.000,78.000,75.000,74.000,72.000,75.000,72.000,74.000,94.000,110.000,28.000,74.000,74.000,73.000,67.000,66.000,67.000,66.000,63.000,59.000,62.000,58.000,56.000,58.000,58.000,54.000,46.000,30.000,19.000,28.000,25.000,30.000,31.000,27.000}
-63.435 LMS_LASER_2D_LEFT LMS1 ID=4162,time=1225719875.075566,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=159,Range=[181]{1.041,1.053,1.055,1.067,1.070,1.081,1.089,1.108,1.108,1.119,1.131,1.148,1.152,1.170,1.181,1.191,1.210,1.222,1.225,1.246,1.257,1.271,1.288,1.305,1.315,1.339,1.345,1.364,1.384,1.410,1.425,1.457,1.475,1.509,1.539,1.569,1.602,1.620,1.627,1.643,1.688,1.706,1.733,1.776,1.806,1.837,1.868,1.912,1.960,2.005,2.039,2.090,2.144,2.197,2.247,2.309,2.356,2.379,2.420,2.547,2.600,2.666,2.659,2.673,2.760,2.843,2.920,2.987,3.069,3.182,3.279,3.363,3.543,3.710,3.813,3.952,3.982,3.972,3.976,4.013,4.038,4.049,4.049,4.049,4.059,4.060,4.052,4.075,4.112,4.144,4.156,4.147,4.174,4.176,4.171,4.174,4.174,4.180,4.190,4.191,4.198,4.198,4.199,4.207,4.208,4.217,4.217,4.226,4.226,4.237,4.243,4.250,4.259,4.268,2.861,2.903,2.821,2.806,2.814,2.773,2.788,2.915,2.955,2.956,2.959,2.887,2.963,2.977,3.111,3.151,3.145,3.135,3.118,3.111,3.098,3.080,3.072,3.051,3.043,3.032,3.026,3.014,3.005,2.993,2.998,3.000,2.995,2.995,2.980,2.976,2.993,3.070,3.163,3.227,3.132,5.028,5.057,5.081,5.113,5.141,5.175,5.210,5.234,5.267,5.310,5.364,5.404,5.442,5.451,5.486,5.522,5.476,5.507,5.830,6.591,6.629,6.653,6.768,6.812,6.871,6.921},Reflectance=[181]{43.000,40.000,38.000,39.000,40.000,45.000,46.000,42.000,47.000,43.000,41.000,45.000,43.000,44.000,46.000,45.000,38.000,40.000,42.000,43.000,46.000,43.000,47.000,42.000,48.000,45.000,49.000,53.000,54.000,47.000,50.000,49.000,52.000,49.000,46.000,43.000,42.000,42.000,55.000,54.000,50.000,57.000,54.000,53.000,55.000,53.000,54.000,51.000,53.000,54.000,45.000,42.000,43.000,38.000,35.000,37.000,43.000,69.000,56.000,54.000,53.000,50.000,51.000,57.000,56.000,47.000,51.000,51.000,48.000,47.000,47.000,46.000,44.000,55.000,67.000,77.000,74.000,69.000,70.000,73.000,75.000,75.000,75.000,75.000,73.000,66.000,71.000,72.000,71.000,72.000,75.000,75.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,33.000,86.000,75.000,76.000,76.000,74.000,73.000,81.000,81.000,77.000,78.000,70.000,74.000,66.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,77.000,77.000,77.000,76.000,74.000,76.000,70.000,60.000,74.000,74.000,77.000,76.000,73.000,87.000,93.000,112.000,34.000,71.000,72.000,72.000,73.000,74.000,74.000,71.000,68.000,67.000,65.000,61.000,58.000,59.000,59.000,60.000,56.000,59.000,57.000,48.000,28.000,17.000,28.000,23.000,29.000,31.000,26.000}
-63.435 LMS_LASER_2D_RIGHT LMS2 ID=4035,time=1225719875.081103,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=124,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,22.345,15.130,12.718,10.872,9.748,8.917,8.044,7.279,6.711,6.201,5.823,5.494,5.112,4.807,4.519,4.238,4.045,3.840,3.636,3.431,3.292,3.144,2.993,2.835,2.762,2.679,2.588,2.505,2.414,2.327,2.246,2.166,2.122,2.054,1.993,1.944,1.892,1.808,1.765,1.743,1.699,1.670,1.643,1.607,1.588,1.550,1.515,1.466,1.454,1.434,1.405,1.389,1.356,1.330,1.313,1.288,1.266,1.244,1.211,1.196,1.191,1.180,1.180,1.175,1.187,1.190,1.207,1.216,1.215,1.193,1.186,1.167,1.152,1.142,1.119,1.131,1.122,1.098,1.076,1.056,1.056,1.057,1.050,1.044,1.041,1.005,1.019,1.018,1.006,0.986,0.953},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,17.000,130.000,104.000,84.000,63.000,57.000,57.000,56.000,61.000,68.000,68.000,67.000,70.000,69.000,73.000,72.000,72.000,75.000,76.000,77.000,79.000,77.000,76.000,82.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,76.000,77.000,78.000,77.000,77.000,77.000,75.000,69.000,69.000,71.000,75.000,73.000,74.000,77.000,78.000,77.000,77.000,71.000,63.000,56.000,45.000,40.000,44.000,54.000,54.000,57.000,58.000,58.000,64.000,49.000,42.000,46.000,39.000,40.000,42.000,38.000,34.000,32.000,33.000,27.000,33.000,37.000,34.000,30.000,28.000}
-63.446 LMS_LASER_2D_LEFT LMS1 ID=4163,time=1225719875.088908,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=160,Range=[181]{1.038,1.043,1.058,1.067,1.075,1.083,1.090,1.105,1.104,1.124,1.133,1.144,1.163,1.169,1.178,1.198,1.210,1.224,1.223,1.243,1.259,1.272,1.285,1.300,1.321,1.333,1.349,1.367,1.387,1.404,1.427,1.454,1.471,1.499,1.530,1.559,1.593,1.608,1.643,1.663,1.682,1.696,1.704,1.770,1.809,1.844,1.871,1.903,1.947,1.982,2.039,2.085,2.144,2.188,2.233,2.295,2.338,2.385,2.429,2.546,2.606,2.657,2.657,2.670,2.759,2.814,2.887,2.926,3.049,3.158,3.257,3.346,3.473,3.665,3.781,3.914,3.972,3.968,3.973,3.998,4.030,4.039,4.049,4.049,4.054,4.067,4.054,4.069,4.103,4.138,4.147,4.147,4.173,4.170,4.164,4.174,4.174,4.174,4.182,4.191,4.192,4.197,4.203,4.198,4.209,4.206,4.194,4.217,4.227,4.234,4.244,4.252,4.258,4.269,4.277,3.015,2.895,2.865,2.793,2.815,2.838,2.887,2.885,2.970,3.106,2.927,2.949,2.972,3.120,3.156,3.147,3.137,3.123,3.114,3.105,3.094,3.080,3.060,3.052,3.048,3.036,3.020,3.021,3.020,3.023,3.024,3.023,3.102,3.113,3.137,3.216,3.127,4.931,4.958,4.990,5.020,5.052,5.069,5.093,5.134,5.160,5.194,5.220,5.261,5.301,5.352,5.395,5.434,5.451,5.474,5.518,5.495,5.493,5.747,6.575,6.599,6.652,6.745,6.797,6.860,6.883},Reflectance=[181]{41.000,39.000,38.000,38.000,36.000,42.000,45.000,41.000,49.000,45.000,36.000,35.000,40.000,43.000,39.000,40.000,43.000,45.000,46.000,42.000,41.000,43.000,45.000,44.000,45.000,43.000,47.000,51.000,48.000,48.000,47.000,47.000,51.000,43.000,46.000,43.000,47.000,46.000,41.000,42.000,47.000,62.000,63.000,51.000,52.000,44.000,48.000,54.000,55.000,51.000,46.000,39.000,39.000,43.000,43.000,43.000,48.000,56.000,56.000,46.000,52.000,50.000,50.000,55.000,55.000,56.000,59.000,61.000,51.000,48.000,49.000,50.000,50.000,50.000,60.000,76.000,76.000,72.000,71.000,71.000,73.000,75.000,75.000,75.000,74.000,70.000,72.000,71.000,71.000,73.000,75.000,75.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,79.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,80.000,78.000,78.000,113.000,81.000,80.000,72.000,74.000,75.000,79.000,76.000,84.000,78.000,76.000,68.000,67.000,79.000,80.000,79.000,79.000,78.000,78.000,76.000,77.000,78.000,78.000,78.000,72.000,71.000,66.000,67.000,65.000,72.000,75.000,74.000,87.000,91.000,95.000,109.000,26.000,76.000,77.000,76.000,71.000,73.000,73.000,72.000,74.000,74.000,72.000,69.000,68.000,65.000,60.000,58.000,59.000,60.000,58.000,54.000,60.000,59.000,46.000,24.000,25.000,28.000,22.000,29.000,30.000,27.000}
-63.446 LMS_LASER_2D_RIGHT LMS2 ID=4036,time=1225719875.094440,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=125,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.182,13.069,11.231,9.978,9.050,8.229,7.406,6.798,6.281,5.912,5.543,5.184,4.845,4.572,4.273,4.099,3.886,3.680,3.457,3.311,3.179,3.003,2.865,2.770,2.706,2.613,2.507,2.441,2.344,2.264,2.184,2.122,2.079,2.017,1.958,1.910,1.798,1.763,1.752,1.716,1.679,1.643,1.616,1.596,1.559,1.519,1.484,1.454,1.438,1.408,1.376,1.349,1.313,1.302,1.280,1.271,1.236,1.210,1.211,1.200,1.183,1.177,1.175,1.187,1.195,1.205,1.217,1.214,1.199,1.190,1.178,1.158,1.149,1.132,1.124,1.126,1.110,1.090,1.057,1.057,1.060,1.060,1.054,1.033,0.998,0.996,1.019,1.010,0.995,0.983},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,103.000,118.000,88.000,67.000,58.000,56.000,56.000,61.000,68.000,67.000,67.000,70.000,69.000,73.000,72.000,72.000,74.000,76.000,77.000,77.000,77.000,76.000,81.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,75.000,70.000,60.000,66.000,74.000,77.000,73.000,74.000,77.000,78.000,78.000,76.000,72.000,63.000,55.000,48.000,40.000,41.000,52.000,56.000,55.000,57.000,57.000,61.000,53.000,47.000,47.000,42.000,36.000,41.000,41.000,41.000,37.000,33.000,27.000,29.000,37.000,35.000,34.000,32.000}
-63.451 DESIRED_THRUST iJoystick 86.60237434
-63.451 DESIRED_RUDDER iJoystick 0
-63.475 DESIRED_THRUST iJoystick 86.60237434
-63.475 DESIRED_RUDDER iJoystick 0
-63.475 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.6084,19.7663,-0.9284},Vel=[3x1]{-0.9096,-0.6806,10.6410},Raw=[2x1]{21.8476,-0.9284},time=1225719875.12246799468994,Speed=1.13606495137408,Pitch=0.04486707467677,Roll=0.03589365974142,PitchDot=0.00897341493535,RollDot=-0.00154791407635
-63.475 ODOMETRY_POSE iPlatform Pose=[3x1]{5.6084,19.7663,-0.9275},Vel=[3x1]{-0.9096,-0.6806,-1.9254},Raw=[2x1]{21.8476,-0.9284},time=1225719875.1225,Speed=1.1361,Pitch=-0.0018,Roll=0.0574,PitchDot=-0.0017,RollDot=0.0090
-63.458 LMS_LASER_2D_LEFT LMS1 ID=4164,time=1225719875.102248,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=161,Range=[181]{1.039,1.046,1.061,1.067,1.073,1.085,1.085,1.088,1.098,1.122,1.136,1.145,1.154,1.160,1.172,1.191,1.199,1.212,1.229,1.236,1.253,1.268,1.286,1.293,1.311,1.327,1.344,1.358,1.378,1.399,1.415,1.440,1.465,1.498,1.524,1.555,1.578,1.605,1.635,1.653,1.679,1.708,1.702,1.704,1.796,1.826,1.864,1.901,1.940,1.988,2.017,2.060,2.124,2.177,2.222,2.274,2.308,2.389,2.456,2.512,2.579,2.649,2.656,2.652,2.729,2.812,2.886,2.901,3.019,3.114,3.226,3.328,3.451,3.608,3.735,3.905,3.978,3.965,3.963,3.992,4.019,4.039,4.049,4.044,4.053,4.064,4.053,4.058,4.092,4.127,4.146,4.141,4.165,4.172,4.166,4.174,4.175,4.174,4.180,4.182,4.188,4.198,4.204,4.199,4.197,4.207,4.216,4.218,4.217,4.227,4.235,4.244,4.252,4.260,3.506,3.075,3.257,3.239,3.192,2.890,2.997,2.980,2.890,2.908,2.937,2.920,3.072,3.164,3.159,3.160,3.148,3.147,3.138,3.126,3.129,3.108,3.105,3.098,3.096,3.088,3.094,3.072,3.068,3.075,3.207,3.230,3.112,4.786,4.815,3.308,3.216,4.891,4.913,4.949,4.973,5.010,5.045,5.057,5.091,5.117,5.155,5.185,5.219,5.247,5.282,5.328,5.379,5.421,5.447,5.463,5.504,5.495,5.478,5.620,6.542,6.594,6.653,6.695,6.786,6.820,6.865},Reflectance=[181]{42.000,45.000,40.000,39.000,42.000,40.000,39.000,53.000,46.000,38.000,39.000,36.000,37.000,43.000,41.000,45.000,46.000,44.000,39.000,43.000,47.000,45.000,45.000,46.000,45.000,49.000,49.000,51.000,48.000,49.000,50.000,49.000,48.000,43.000,43.000,50.000,52.000,43.000,45.000,46.000,50.000,54.000,71.000,66.000,50.000,48.000,49.000,50.000,48.000,45.000,48.000,48.000,42.000,45.000,42.000,50.000,50.000,50.000,49.000,51.000,56.000,50.000,50.000,56.000,58.000,55.000,58.000,65.000,56.000,49.000,47.000,45.000,49.000,50.000,58.000,71.000,75.000,71.000,71.000,72.000,72.000,75.000,75.000,74.000,74.000,72.000,71.000,70.000,70.000,72.000,75.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,103.000,99.000,80.000,78.000,80.000,82.000,86.000,86.000,75.000,76.000,74.000,74.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,77.000,75.000,74.000,76.000,62.000,60.000,61.000,55.000,63.000,68.000,70.000,94.000,107.000,36.000,77.000,78.000,8.000,33.000,77.000,76.000,77.000,76.000,71.000,73.000,75.000,75.000,75.000,75.000,74.000,71.000,69.000,66.000,62.000,59.000,58.000,58.000,57.000,59.000,59.000,59.000,45.000,27.000,32.000,24.000,23.000,29.000,32.000,31.000}
-63.459 LMS_LASER_2D_RIGHT LMS2 ID=4037,time=1225719875.107775,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=126,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.518,16.543,13.677,11.554,10.134,9.231,8.453,7.604,6.955,6.484,6.008,5.612,5.274,4.899,4.640,4.322,4.151,3.928,3.729,3.486,3.348,3.210,3.021,2.917,2.799,2.728,2.630,2.544,2.441,2.359,2.274,2.209,2.141,2.087,2.034,1.976,1.924,1.855,1.779,1.759,1.729,1.684,1.661,1.625,1.602,1.569,1.530,1.494,1.470,1.438,1.411,1.379,1.351,1.313,1.298,1.285,1.265,1.241,1.219,1.214,1.198,1.198,1.184,1.176,1.187,1.192,1.209,1.212,1.214,1.199,1.189,1.177,1.173,1.163,1.141,1.122,1.114,1.106,1.096,1.064,1.054,1.061,1.067,1.057,1.053,1.011,0.986,1.021,1.005,1.002,0.988},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,94.000,116.000,90.000,71.000,60.000,54.000,57.000,59.000,65.000,68.000,67.000,70.000,70.000,73.000,72.000,72.000,74.000,75.000,77.000,77.000,78.000,75.000,78.000,81.000,79.000,79.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,73.000,71.000,74.000,78.000,77.000,75.000,76.000,78.000,78.000,78.000,76.000,72.000,63.000,57.000,50.000,38.000,44.000,57.000,56.000,58.000,53.000,52.000,53.000,56.000,56.000,49.000,45.000,36.000,37.000,40.000,43.000,46.000,39.000,29.000,27.000,38.000,32.000,33.000,32.000}
-63.471 LMS_LASER_2D_LEFT LMS1 ID=4165,time=1225719875.115588,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=162,Range=[181]{1.038,1.048,1.048,1.063,1.076,1.071,1.083,1.097,1.095,1.119,1.130,1.139,1.147,1.160,1.172,1.183,1.200,1.206,1.221,1.230,1.241,1.260,1.280,1.282,1.307,1.317,1.338,1.357,1.379,1.391,1.413,1.434,1.464,1.495,1.522,1.542,1.569,1.600,1.634,1.653,1.675,1.698,1.723,1.714,1.739,1.813,1.849,1.887,1.931,1.974,2.008,2.050,2.111,2.158,2.216,2.262,2.319,2.373,2.425,2.502,2.570,2.641,2.656,2.640,2.699,2.808,2.873,2.914,2.994,3.078,3.215,3.287,3.403,3.546,3.674,3.859,3.971,3.967,3.961,3.971,4.009,4.030,4.039,4.044,4.044,4.053,4.045,4.047,4.074,4.112,4.144,4.139,4.146,4.161,4.166,4.166,4.165,4.173,4.179,4.179,4.184,4.195,4.199,4.199,4.199,4.199,4.208,4.208,4.220,4.229,4.226,4.234,4.243,3.462,3.307,3.270,3.248,3.239,3.233,3.038,3.212,3.210,2.985,2.927,2.954,2.980,3.179,3.173,3.181,3.182,3.172,3.161,3.158,3.149,3.147,3.145,3.137,3.152,3.143,3.166,3.245,3.259,3.280,3.164,4.713,4.739,4.759,4.781,4.807,3.275,3.333,4.881,4.913,4.940,4.966,4.998,5.037,5.052,5.078,5.111,5.138,5.169,5.205,5.238,5.270,5.310,5.354,5.404,5.446,5.446,5.481,5.489,5.474,5.530,5.925,6.569,6.632,6.638,6.756,6.801,6.864},Reflectance=[181]{37.000,42.000,38.000,40.000,39.000,41.000,34.000,35.000,33.000,40.000,41.000,40.000,41.000,43.000,41.000,42.000,42.000,41.000,44.000,44.000,46.000,42.000,43.000,49.000,48.000,49.000,50.000,46.000,48.000,49.000,49.000,50.000,48.000,45.000,42.000,52.000,52.000,45.000,41.000,45.000,48.000,54.000,54.000,65.000,61.000,54.000,50.000,55.000,52.000,43.000,48.000,43.000,44.000,41.000,39.000,48.000,42.000,47.000,51.000,45.000,52.000,51.000,49.000,55.000,56.000,50.000,52.000,55.000,50.000,56.000,46.000,51.000,51.000,50.000,54.000,70.000,75.000,74.000,70.000,71.000,74.000,75.000,75.000,74.000,74.000,71.000,69.000,72.000,70.000,71.000,75.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,102.000,82.000,79.000,79.000,79.000,79.000,85.000,79.000,80.000,85.000,78.000,77.000,81.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,75.000,75.000,72.000,62.000,71.000,78.000,96.000,101.000,110.000,36.000,78.000,78.000,79.000,78.000,78.000,31.000,95.000,77.000,76.000,77.000,76.000,73.000,76.000,75.000,75.000,75.000,75.000,75.000,72.000,71.000,68.000,66.000,61.000,58.000,58.000,57.000,62.000,63.000,58.000,55.000,54.000,30.000,21.000,26.000,28.000,32.000,33.000}
-63.482 LMS_LASER_2D_LEFT LMS1 ID=4166,time=1225719875.128925,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=163,Range=[181]{1.032,1.044,1.047,1.054,1.066,1.077,1.077,1.085,1.103,1.115,1.127,1.133,1.141,1.163,1.168,1.174,1.191,1.207,1.217,1.227,1.245,1.254,1.268,1.289,1.296,1.313,1.326,1.349,1.375,1.392,1.408,1.435,1.448,1.476,1.504,1.537,1.556,1.592,1.606,1.629,1.663,1.697,1.711,1.734,1.768,1.811,1.839,1.875,1.903,1.964,1.993,2.041,2.090,2.142,2.185,2.243,2.301,2.356,2.413,2.479,2.548,2.617,2.650,2.646,2.681,2.801,2.854,2.911,2.984,3.082,3.175,3.258,3.360,3.509,3.590,3.619,3.702,3.717,3.739,3.782,3.894,4.017,4.031,4.035,4.033,4.044,4.047,4.037,4.061,4.104,4.128,4.138,4.139,4.159,4.163,4.164,4.165,4.167,4.171,4.172,4.180,4.192,4.195,4.199,4.198,4.199,4.202,4.209,4.208,4.217,4.197,3.495,3.370,3.290,3.270,3.248,3.240,3.236,3.236,3.233,3.221,3.210,3.212,3.128,3.204,3.199,3.199,3.195,3.201,3.201,3.200,3.198,3.201,3.197,3.196,3.201,3.232,3.300,3.365,4.596,4.619,4.635,4.662,4.678,4.706,4.732,4.747,4.774,4.791,3.411,3.331,4.867,4.891,4.926,4.953,4.982,5.017,5.035,5.069,5.095,5.129,5.165,5.191,5.229,5.252,5.298,5.337,5.384,5.432,5.451,5.463,5.480,5.474,5.478,5.749,6.518,6.570,6.614,6.674,6.752,6.822},Reflectance=[181]{42.000,37.000,34.000,35.000,42.000,37.000,33.000,35.000,37.000,41.000,40.000,38.000,42.000,40.000,43.000,46.000,42.000,41.000,38.000,43.000,43.000,48.000,46.000,43.000,47.000,51.000,49.000,47.000,46.000,45.000,46.000,45.000,49.000,49.000,45.000,49.000,46.000,46.000,46.000,48.000,46.000,49.000,52.000,55.000,54.000,53.000,54.000,53.000,54.000,42.000,49.000,43.000,42.000,42.000,46.000,43.000,45.000,52.000,49.000,51.000,54.000,56.000,51.000,53.000,56.000,47.000,48.000,50.000,49.000,54.000,48.000,45.000,52.000,45.000,53.000,58.000,75.000,79.000,76.000,75.000,73.000,74.000,75.000,74.000,74.000,72.000,70.000,72.000,71.000,71.000,72.000,75.000,76.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,80.000,101.000,88.000,78.000,79.000,79.000,79.000,80.000,80.000,79.000,79.000,78.000,79.000,81.000,78.000,77.000,77.000,76.000,75.000,75.000,75.000,75.000,73.000,72.000,71.000,73.000,81.000,98.000,109.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,110.000,101.000,77.000,77.000,77.000,78.000,76.000,76.000,76.000,75.000,76.000,75.000,76.000,73.000,71.000,68.000,68.000,63.000,57.000,59.000,60.000,61.000,66.000,58.000,59.000,55.000,30.000,28.000,30.000,32.000,32.000,33.000}
-63.482 LMS_LASER_2D_RIGHT LMS2 ID=4038,time=1225719875.121120,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=127,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.354,17.314,14.238,12.000,10.495,9.480,8.633,7.747,7.088,6.598,6.081,5.698,5.372,4.990,4.724,4.412,4.194,3.990,3.774,3.533,3.377,3.233,3.064,2.957,2.826,2.734,2.654,2.561,2.468,2.389,2.300,2.227,2.167,2.097,2.044,1.985,1.935,1.881,1.815,1.776,1.716,1.685,1.661,1.635,1.607,1.570,1.540,1.510,1.472,1.445,1.419,1.393,1.371,1.339,1.323,1.300,1.272,1.249,1.231,1.216,1.208,1.195,1.194,1.176,1.187,1.198,1.207,1.216,1.216,1.196,1.191,1.183,1.174,1.166,1.153,1.137,1.120,1.110,1.103,1.056,1.059,1.061,1.060,1.058,1.052,0.996,0.992,1.019,1.014,0.995,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,73.000,125.000,98.000,78.000,60.000,56.000,58.000,57.000,64.000,69.000,67.000,69.000,70.000,71.000,72.000,72.000,74.000,74.000,77.000,78.000,77.000,78.000,77.000,81.000,78.000,78.000,81.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,79.000,76.000,75.000,79.000,79.000,79.000,78.000,78.000,77.000,76.000,78.000,78.000,78.000,77.000,75.000,76.000,77.000,77.000,75.000,78.000,78.000,78.000,77.000,77.000,73.000,64.000,52.000,45.000,37.000,49.000,59.000,57.000,61.000,57.000,50.000,51.000,51.000,51.000,51.000,42.000,32.000,41.000,42.000,39.000,41.000,37.000,27.000,27.000,33.000,36.000,31.000,33.000}
-63.499 DESIRED_THRUST iJoystick 86.60237434
-63.499 DESIRED_RUDDER iJoystick 0
-63.494 LMS_LASER_2D_RIGHT LMS2 ID=4039,time=1225719875.134464,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=128,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.156,18.108,15.178,12.647,10.826,9.711,8.852,7.939,7.213,6.713,6.201,5.813,5.477,5.094,4.791,4.501,4.239,4.064,3.817,3.610,3.413,3.259,3.122,2.961,2.885,2.758,2.666,2.587,2.496,2.414,2.328,2.256,2.185,2.114,2.061,2.002,1.944,1.889,1.837,1.793,1.728,1.698,1.672,1.643,1.617,1.589,1.551,1.521,1.481,1.451,1.429,1.402,1.381,1.352,1.324,1.297,1.268,1.238,1.230,1.226,1.209,1.205,1.196,1.184,1.188,1.203,1.212,1.214,1.221,1.200,1.191,1.178,1.169,1.162,1.145,1.140,1.124,1.110,1.103,1.033,1.057,1.067,1.063,1.061,1.063,1.049,0.992,1.019,1.015,0.998,0.965},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,31.000,11.000,122.000,103.000,83.000,63.000,56.000,59.000,54.000,62.000,69.000,68.000,68.000,70.000,70.000,73.000,73.000,73.000,74.000,76.000,77.000,77.000,77.000,78.000,81.000,80.000,72.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,76.000,76.000,80.000,79.000,80.000,79.000,78.000,77.000,75.000,77.000,78.000,78.000,77.000,77.000,77.000,76.000,75.000,74.000,77.000,78.000,78.000,77.000,77.000,73.000,66.000,54.000,47.000,39.000,38.000,57.000,61.000,63.000,62.000,55.000,55.000,53.000,53.000,51.000,42.000,28.000,38.000,43.000,42.000,39.000,48.000,41.000,27.000,32.000,34.000,33.000,29.000}
-63.506 LMS_LASER_2D_RIGHT LMS2 ID=4040,time=1225719875.147808,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=129,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,21.961,16.030,13.076,11.177,9.979,9.059,8.279,7.434,6.849,6.324,5.937,5.560,5.184,4.855,4.597,4.301,4.126,3.892,3.680,3.468,3.316,3.169,2.984,2.907,2.804,2.692,2.610,2.533,2.441,2.353,2.274,2.201,2.131,2.086,2.019,1.961,1.908,1.855,1.803,1.755,1.721,1.690,1.643,1.616,1.590,1.562,1.534,1.493,1.457,1.434,1.418,1.389,1.365,1.337,1.302,1.262,1.248,1.241,1.227,1.216,1.206,1.199,1.192,1.190,1.191,1.207,1.214,1.221,1.216,1.195,1.178,1.170,1.163,1.149,1.135,1.130,1.123,1.110,1.082,1.056,1.057,1.067,1.068,1.059,1.049,0.998,1.008,1.027,1.006,0.997},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,112.000,114.000,86.000,68.000,59.000,55.000,57.000,60.000,67.000,67.000,67.000,70.000,69.000,73.000,73.000,73.000,72.000,76.000,77.000,76.000,77.000,78.000,80.000,80.000,71.000,76.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,80.000,79.000,79.000,80.000,79.000,78.000,74.000,73.000,77.000,78.000,77.000,75.000,75.000,75.000,74.000,75.000,75.000,77.000,75.000,78.000,78.000,76.000,69.000,57.000,48.000,39.000,38.000,56.000,63.000,63.000,63.000,59.000,61.000,58.000,52.000,49.000,41.000,36.000,36.000,43.000,43.000,43.000,41.000,43.000,27.000,29.000,35.000,34.000,31.000}
-63.511 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.6357,19.7867,-0.9337},Vel=[3x1]{-0.9085,-0.6723,10.0000},Raw=[2x1]{21.8817,-0.9337},time=1225719875.15845394134521,Speed=1.13022400046728,Pitch=0.04486707467677,Roll=0.03365030600758,PitchDot=0.01570347613687,RollDot=-0.00210875250981
-63.511 ODOMETRY_POSE iPlatform Pose=[3x1]{5.6357,19.7867,-0.9329},Vel=[3x1]{-0.9085,-0.6723,-2.5663},Raw=[2x1]{21.8817,-0.9337},time=1225719875.1585,Speed=1.1302,Pitch=-0.0003,Roll=0.0561,PitchDot=-0.0120,RollDot=0.0103
-63.523 DESIRED_THRUST iJoystick 86.60237434
-63.523 DESIRED_RUDDER iJoystick 0
-63.494 LMS_LASER_2D_LEFT LMS1 ID=4167,time=1225719875.142261,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=164,Range=[181]{1.029,1.038,1.038,1.060,1.054,1.073,1.074,1.082,1.099,1.107,1.122,1.126,1.141,1.151,1.168,1.174,1.185,1.199,1.212,1.223,1.233,1.247,1.258,1.277,1.286,1.307,1.328,1.343,1.362,1.381,1.395,1.424,1.441,1.471,1.497,1.518,1.553,1.583,1.606,1.627,1.663,1.684,1.709,1.732,1.760,1.786,1.827,1.869,1.898,1.938,1.981,2.035,2.073,2.124,2.179,2.225,2.291,2.336,2.403,2.465,2.527,2.610,2.647,2.639,2.662,2.769,2.835,2.884,2.974,3.054,3.137,3.241,3.328,3.446,3.560,3.571,3.569,3.559,3.535,3.530,3.520,3.516,3.514,3.514,3.542,3.555,3.521,3.479,3.500,3.531,3.537,3.545,3.560,3.564,3.572,3.565,3.627,3.726,4.125,4.161,4.174,4.180,4.186,4.196,4.197,4.196,4.199,4.149,3.532,3.434,3.320,3.293,3.280,3.263,3.257,3.251,3.240,3.239,3.239,3.239,3.239,3.236,3.219,3.230,3.237,3.234,3.239,3.245,3.258,3.255,3.266,3.258,3.322,3.350,3.374,3.409,4.540,4.559,4.570,4.595,4.604,4.628,4.653,4.670,4.696,4.714,4.739,4.758,4.779,3.421,3.172,4.857,4.883,4.907,4.941,4.966,4.992,5.019,5.046,5.079,5.116,5.148,5.181,5.213,5.241,5.277,5.319,5.368,5.405,5.454,5.440,5.480,5.481,5.462,5.582,6.533,6.577,6.625,6.646,6.743,6.800},Reflectance=[181]{40.000,41.000,41.000,40.000,34.000,42.000,36.000,42.000,42.000,45.000,40.000,43.000,42.000,43.000,39.000,42.000,43.000,45.000,37.000,41.000,45.000,49.000,46.000,45.000,46.000,48.000,46.000,48.000,44.000,44.000,51.000,49.000,53.000,51.000,51.000,49.000,44.000,37.000,44.000,42.000,45.000,52.000,55.000,54.000,54.000,54.000,52.000,51.000,52.000,47.000,54.000,40.000,42.000,42.000,38.000,43.000,44.000,50.000,49.000,49.000,49.000,50.000,49.000,50.000,56.000,48.000,51.000,53.000,49.000,53.000,55.000,46.000,46.000,46.000,56.000,57.000,52.000,55.000,63.000,70.000,70.000,72.000,71.000,74.000,80.000,83.000,82.000,79.000,82.000,85.000,88.000,91.000,92.000,95.000,96.000,96.000,95.000,93.000,79.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,80.000,99.000,100.000,77.000,76.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,76.000,72.000,72.000,71.000,71.000,72.000,84.000,95.000,102.000,108.000,76.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,111.000,32.000,77.000,77.000,77.000,77.000,76.000,76.000,76.000,76.000,76.000,77.000,76.000,75.000,72.000,70.000,67.000,64.000,59.000,55.000,53.000,59.000,66.000,61.000,61.000,52.000,26.000,31.000,27.000,31.000,32.000,34.000}
-63.518 LMS_LASER_2D_LEFT LMS1 ID=4168,time=1225719875.155607,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=165,Range=[181]{1.022,1.038,1.047,1.047,1.058,1.063,1.073,1.088,1.093,1.098,1.112,1.120,1.131,1.142,1.157,1.165,1.182,1.191,1.202,1.219,1.227,1.245,1.258,1.271,1.293,1.308,1.319,1.342,1.355,1.376,1.389,1.416,1.435,1.461,1.487,1.511,1.542,1.566,1.600,1.627,1.646,1.668,1.697,1.724,1.741,1.778,1.814,1.853,1.894,1.947,1.972,2.001,2.065,2.098,2.159,2.201,2.266,2.319,2.380,2.431,2.502,2.583,2.643,2.640,2.640,2.707,2.810,2.864,2.944,3.023,3.113,3.185,3.285,3.391,3.524,3.537,3.541,3.524,3.506,3.505,3.498,3.490,3.479,3.471,3.457,3.450,3.430,3.422,3.413,3.407,3.397,3.390,3.378,3.371,3.362,3.359,3.350,3.355,3.343,3.345,3.353,3.381,3.406,3.400,3.391,3.378,3.342,3.313,3.294,3.279,3.279,3.264,3.257,3.258,3.249,3.248,3.248,3.245,3.252,3.242,3.251,3.251,3.242,3.243,3.263,3.303,3.328,3.344,3.394,3.412,3.472,4.438,4.457,4.475,4.493,4.512,4.534,4.542,4.562,4.579,4.594,4.618,4.635,4.660,4.680,4.707,4.724,4.742,4.773,4.796,4.815,4.842,4.875,4.900,4.925,4.958,4.975,5.014,5.040,5.066,5.098,5.132,5.157,5.191,5.227,5.254,5.301,5.346,5.390,5.435,5.439,5.479,5.491,5.454,5.498,5.852,6.566,6.636,6.643,6.753,6.793},Reflectance=[181]{42.000,38.000,41.000,41.000,38.000,41.000,42.000,40.000,43.000,46.000,40.000,44.000,46.000,42.000,45.000,41.000,45.000,46.000,43.000,43.000,43.000,43.000,45.000,43.000,41.000,44.000,46.000,43.000,46.000,47.000,49.000,53.000,45.000,45.000,45.000,46.000,48.000,47.000,40.000,42.000,47.000,53.000,53.000,54.000,54.000,54.000,54.000,51.000,46.000,38.000,54.000,52.000,42.000,46.000,46.000,50.000,46.000,51.000,54.000,53.000,50.000,46.000,48.000,51.000,55.000,56.000,51.000,49.000,45.000,47.000,56.000,52.000,46.000,45.000,62.000,69.000,55.000,57.000,69.000,74.000,75.000,75.000,74.000,75.000,75.000,76.000,75.000,76.000,76.000,77.000,76.000,77.000,76.000,76.000,76.000,75.000,75.000,77.000,76.000,76.000,79.000,84.000,89.000,89.000,90.000,91.000,83.000,77.000,77.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,75.000,74.000,74.000,78.000,91.000,95.000,103.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,73.000,71.000,68.000,65.000,61.000,56.000,52.000,58.000,60.000,58.000,63.000,61.000,53.000,32.000,20.000,27.000,31.000,35.000}
-63.518 LMS_LASER_2D_RIGHT LMS2 ID=4041,time=1225719875.161149,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=130,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,27.194,17.026,13.924,11.834,10.299,9.337,8.510,7.632,7.032,6.554,6.052,5.664,5.319,4.926,4.699,4.385,4.177,3.946,3.741,3.513,3.367,3.215,3.004,2.945,2.848,2.715,2.619,2.560,2.469,2.385,2.292,2.219,2.156,2.113,2.044,1.969,1.927,1.866,1.821,1.776,1.740,1.690,1.653,1.621,1.607,1.572,1.534,1.507,1.473,1.440,1.427,1.405,1.375,1.339,1.317,1.295,1.267,1.249,1.247,1.219,1.209,1.201,1.191,1.186,1.201,1.212,1.224,1.229,1.211,1.195,1.187,1.173,1.161,1.146,1.139,1.131,1.126,1.115,1.099,1.046,1.059,1.067,1.077,1.061,1.046,1.031,0.998,1.024,0.982,0.964},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,2.000,82.000,121.000,91.000,75.000,59.000,56.000,58.000,56.000,64.000,67.000,67.000,69.000,70.000,72.000,72.000,73.000,73.000,74.000,77.000,78.000,77.000,79.000,79.000,80.000,75.000,73.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,80.000,79.000,78.000,79.000,79.000,78.000,76.000,70.000,76.000,78.000,77.000,75.000,75.000,74.000,75.000,75.000,75.000,77.000,77.000,78.000,79.000,78.000,74.000,61.000,51.000,44.000,38.000,54.000,63.000,63.000,60.000,62.000,65.000,56.000,53.000,50.000,49.000,41.000,31.000,39.000,43.000,44.000,44.000,32.000,31.000,27.000,34.000,28.000,27.000}
-63.530 LMS_LASER_2D_LEFT LMS1 ID=4169,time=1225719875.168952,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=166,Range=[181]{1.022,1.029,1.040,1.053,1.054,1.068,1.067,1.072,1.091,1.097,1.105,1.113,1.130,1.141,1.147,1.163,1.174,1.183,1.193,1.215,1.227,1.233,1.255,1.267,1.285,1.300,1.322,1.335,1.350,1.367,1.387,1.401,1.417,1.451,1.475,1.494,1.526,1.556,1.574,1.613,1.645,1.656,1.695,1.717,1.742,1.764,1.804,1.842,1.876,1.924,1.959,1.979,2.046,2.088,2.142,2.188,2.249,2.300,2.343,2.413,2.484,2.548,2.634,2.635,2.635,2.672,2.799,2.848,2.920,2.990,3.069,3.167,3.245,3.338,3.465,3.518,3.515,3.515,3.504,3.487,3.475,3.466,3.466,3.451,3.441,3.433,3.415,3.400,3.390,3.389,3.382,3.375,3.365,3.355,3.348,3.339,3.330,3.324,3.313,3.312,3.307,3.298,3.296,3.287,3.284,3.277,3.274,3.270,3.267,3.253,3.255,3.255,3.248,3.248,3.248,3.248,3.247,3.246,3.252,3.250,3.256,3.266,3.280,3.303,3.388,3.456,3.540,4.376,4.394,4.403,4.421,4.439,4.448,4.465,4.485,4.493,4.518,4.534,4.553,4.572,4.586,4.606,4.629,4.643,4.670,4.688,4.715,4.732,4.757,4.779,4.806,4.833,4.858,4.882,4.917,4.942,4.969,4.988,5.022,5.049,5.081,5.116,5.143,5.181,5.215,5.246,5.283,5.319,5.367,5.425,5.442,5.443,5.489,5.463,5.454,5.702,6.549,6.595,6.640,6.733,6.769},Reflectance=[181]{42.000,38.000,38.000,40.000,41.000,39.000,48.000,46.000,42.000,41.000,41.000,46.000,41.000,38.000,46.000,44.000,45.000,47.000,43.000,41.000,43.000,46.000,44.000,46.000,45.000,44.000,42.000,44.000,47.000,51.000,48.000,54.000,54.000,50.000,49.000,53.000,52.000,50.000,54.000,43.000,42.000,48.000,39.000,50.000,54.000,56.000,50.000,47.000,46.000,44.000,49.000,54.000,41.000,41.000,45.000,48.000,42.000,46.000,53.000,49.000,50.000,46.000,48.000,52.000,56.000,56.000,46.000,49.000,51.000,49.000,48.000,48.000,48.000,47.000,45.000,75.000,71.000,74.000,76.000,77.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,76.000,77.000,76.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,76.000,76.000,75.000,74.000,85.000,91.000,99.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,76.000,77.000,77.000,75.000,72.000,69.000,65.000,64.000,58.000,56.000,56.000,60.000,61.000,63.000,63.000,56.000,34.000,24.000,26.000,24.000,34.000}
-63.530 LMS_LASER_2D_RIGHT LMS2 ID=4042,time=1225719875.174489,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=131,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.063,18.082,14.944,12.512,10.751,9.657,8.789,7.912,7.189,6.678,6.164,5.759,5.450,5.059,4.775,4.475,4.239,4.026,3.843,3.610,3.406,3.276,3.081,2.969,2.867,2.750,2.646,2.584,2.487,2.411,2.324,2.247,2.174,2.121,2.061,2.002,1.936,1.901,1.838,1.795,1.749,1.708,1.656,1.613,1.614,1.581,1.549,1.515,1.483,1.454,1.426,1.414,1.390,1.363,1.326,1.300,1.277,1.262,1.246,1.221,1.210,1.202,1.192,1.188,1.190,1.204,1.220,1.226,1.226,1.209,1.196,1.182,1.165,1.147,1.142,1.135,1.124,1.113,1.108,1.069,1.060,1.056,1.063,1.062,1.045,1.009,0.999,1.028,1.015,1.002},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,22.000,42.000,120.000,100.000,82.000,63.000,57.000,59.000,55.000,63.000,69.000,67.000,68.000,69.000,72.000,72.000,73.000,73.000,72.000,76.000,78.000,77.000,78.000,78.000,81.000,78.000,69.000,80.000,81.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,80.000,80.000,75.000,78.000,79.000,78.000,78.000,74.000,69.000,75.000,73.000,75.000,75.000,74.000,75.000,76.000,76.000,77.000,77.000,79.000,79.000,78.000,75.000,68.000,59.000,50.000,42.000,45.000,57.000,59.000,57.000,60.000,66.000,61.000,54.000,53.000,52.000,46.000,37.000,39.000,40.000,40.000,45.000,35.000,27.000,28.000,33.000,33.000,32.000}
-63.547 DESIRED_THRUST iJoystick 86.60237434
-63.547 DESIRED_RUDDER iJoystick 0
-63.547 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.6722,19.8134,-0.9411},Vel=[3x1]{-0.9265,-0.6750,11.2821},Raw=[2x1]{21.9269,-0.9411},time=1225719875.19454693794250,Speed=1.14628661546100,Pitch=0.04486707467677,Roll=0.02692024480606,PitchDot=0.00224335373384,RollDot=-0.00195171774844
-63.547 ODOMETRY_POSE iPlatform Pose=[3x1]{5.6722,19.8134,-0.9406},Vel=[3x1]{-0.9265,-0.6750,-1.2843},Raw=[2x1]{21.9269,-0.9411},time=1225719875.1945,Speed=1.1463,Pitch=0.0047,Roll=0.0521,PitchDot=0.0025,RollDot=0.0016
-63.542 LMS_LASER_2D_LEFT LMS1 ID=4170,time=1225719875.182296,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=167,Range=[181]{1.025,1.034,1.034,1.039,1.047,1.061,1.063,1.057,1.076,1.097,1.096,1.117,1.124,1.132,1.141,1.153,1.170,1.174,1.189,1.203,1.208,1.233,1.242,1.264,1.273,1.300,1.302,1.320,1.337,1.358,1.374,1.397,1.418,1.435,1.450,1.495,1.511,1.547,1.568,1.590,1.627,1.654,1.684,1.704,1.733,1.760,1.791,1.822,1.867,1.903,1.948,1.979,2.017,2.070,2.124,2.160,2.219,2.271,2.326,2.394,2.460,2.516,2.589,2.638,2.630,2.663,2.773,2.812,2.878,2.959,3.036,3.134,3.230,3.309,3.394,3.490,3.509,3.501,3.492,3.481,3.472,3.462,3.448,3.438,3.430,3.421,3.400,3.381,3.382,3.364,3.366,3.359,3.349,3.339,3.332,3.321,3.314,3.306,3.296,3.295,3.297,3.286,3.278,3.278,3.267,3.261,3.259,3.250,3.251,3.244,3.245,3.237,3.237,3.239,3.239,3.242,3.242,3.242,3.248,3.252,3.264,3.285,3.311,3.366,3.595,4.353,4.363,4.375,4.385,4.394,4.412,4.430,4.442,4.458,4.476,4.485,4.512,4.525,4.543,4.563,4.588,4.596,4.617,4.635,4.662,4.678,4.705,4.723,4.747,4.772,4.794,4.821,4.851,4.871,4.899,4.925,4.950,4.979,5.014,5.033,5.066,5.096,5.135,5.157,5.197,5.225,5.265,5.300,5.362,5.404,5.440,5.413,5.473,5.472,5.454,5.549,6.519,6.589,6.635,6.674,6.750},Reflectance=[181]{38.000,40.000,40.000,42.000,41.000,44.000,46.000,54.000,48.000,37.000,40.000,42.000,45.000,42.000,42.000,44.000,44.000,45.000,41.000,40.000,45.000,45.000,46.000,44.000,44.000,44.000,49.000,50.000,50.000,47.000,50.000,52.000,54.000,54.000,53.000,46.000,49.000,45.000,48.000,46.000,41.000,41.000,43.000,49.000,54.000,54.000,48.000,46.000,45.000,42.000,39.000,54.000,48.000,44.000,46.000,51.000,49.000,52.000,50.000,49.000,54.000,56.000,52.000,50.000,54.000,56.000,54.000,56.000,55.000,50.000,49.000,46.000,45.000,45.000,48.000,69.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,77.000,75.000,74.000,74.000,81.000,100.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,76.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,76.000,77.000,76.000,72.000,70.000,66.000,66.000,60.000,54.000,55.000,67.000,67.000,64.000,64.000,61.000,35.000,29.000,23.000,26.000,32.000}
-63.542 LMS_LASER_2D_RIGHT LMS2 ID=4043,time=1225719875.187827,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=132,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.288,21.715,15.851,13.018,11.092,9.883,8.979,8.161,7.394,6.823,6.281,5.911,5.544,5.174,4.838,4.571,4.321,4.116,3.892,3.686,3.475,3.316,3.149,2.993,2.954,2.808,2.666,2.600,2.525,2.428,2.344,2.273,2.202,2.139,2.086,2.020,1.961,1.910,1.856,1.806,1.776,1.720,1.668,1.635,1.605,1.598,1.558,1.516,1.490,1.475,1.450,1.423,1.405,1.370,1.333,1.311,1.283,1.262,1.245,1.226,1.215,1.202,1.198,1.186,1.190,1.205,1.216,1.220,1.224,1.220,1.205,1.192,1.165,1.140,1.145,1.133,1.125,1.121,1.112,1.068,1.057,1.059,1.069,1.070,1.051,1.013,1.005,1.031,1.020,1.002},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,32.000,20.000,113.000,112.000,87.000,65.000,58.000,56.000,55.000,60.000,68.000,67.000,68.000,70.000,72.000,71.000,72.000,72.000,72.000,75.000,77.000,78.000,79.000,78.000,79.000,79.000,73.000,79.000,81.000,79.000,77.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,81.000,79.000,78.000,79.000,78.000,78.000,78.000,76.000,77.000,72.000,72.000,73.000,73.000,75.000,75.000,76.000,76.000,76.000,78.000,79.000,78.000,74.000,69.000,60.000,52.000,41.000,39.000,50.000,55.000,53.000,60.000,70.000,63.000,53.000,53.000,52.000,45.000,32.000,34.000,39.000,39.000,44.000,39.000,28.000,27.000,36.000,37.000,32.000}
-63.555 LMS_LASER_2D_LEFT LMS1 ID=4171,time=1225719875.195639,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=168,Range=[181]{1.017,1.029,1.030,1.035,1.051,1.048,1.064,1.049,1.051,1.079,1.101,1.108,1.117,1.128,1.145,1.151,1.159,1.171,1.182,1.193,1.209,1.225,1.237,1.251,1.263,1.277,1.298,1.322,1.344,1.346,1.365,1.387,1.408,1.431,1.456,1.474,1.505,1.539,1.559,1.582,1.607,1.638,1.670,1.696,1.716,1.741,1.778,1.810,1.854,1.897,1.928,1.974,2.005,2.061,2.111,2.154,2.195,2.257,2.319,2.372,2.436,2.481,2.550,2.614,2.628,2.642,2.730,2.812,2.866,2.947,3.005,3.082,3.188,3.271,3.373,3.476,3.502,3.497,3.488,3.478,3.470,3.460,3.443,3.436,3.428,3.410,3.403,3.382,3.367,3.355,3.349,3.341,3.341,3.333,3.316,3.316,3.299,3.299,3.286,3.287,3.280,3.268,3.267,3.259,3.250,3.253,3.245,3.245,3.233,3.234,3.227,3.227,3.228,3.238,3.228,3.230,3.231,3.236,3.245,3.248,3.252,3.278,3.303,3.419,4.337,4.344,4.361,4.365,4.381,4.400,4.408,4.427,4.438,4.447,4.464,4.483,4.500,4.514,4.534,4.551,4.578,4.596,4.607,4.629,4.642,4.669,4.687,4.715,4.730,4.755,4.777,4.803,4.832,4.865,4.887,4.914,4.941,4.968,4.996,5.023,5.060,5.087,5.117,5.150,5.177,5.219,5.252,5.293,5.335,5.393,5.424,5.416,5.449,5.472,5.454,5.481,5.772,6.563,6.611,6.651,6.730},Reflectance=[181]{40.000,41.000,41.000,44.000,39.000,47.000,45.000,58.000,55.000,46.000,43.000,42.000,47.000,44.000,37.000,43.000,42.000,44.000,45.000,43.000,47.000,45.000,43.000,46.000,48.000,50.000,48.000,47.000,44.000,49.000,54.000,52.000,53.000,52.000,52.000,52.000,54.000,45.000,48.000,50.000,54.000,52.000,46.000,49.000,54.000,54.000,54.000,44.000,40.000,43.000,45.000,39.000,45.000,35.000,37.000,48.000,47.000,46.000,45.000,46.000,56.000,60.000,55.000,52.000,50.000,56.000,51.000,48.000,53.000,52.000,48.000,46.000,46.000,48.000,45.000,59.000,76.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,76.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,80.000,80.000,78.000,77.000,75.000,74.000,90.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,79.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,78.000,76.000,77.000,77.000,74.000,71.000,68.000,69.000,60.000,58.000,59.000,68.000,70.000,66.000,64.000,62.000,57.000,32.000,24.000,30.000,32.000}
-63.555 LMS_LASER_2D_LEFT LMS1 ID=4172,time=1225719875.208969,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=169,Range=[181]{1.015,1.023,1.033,1.033,1.048,1.054,1.054,1.028,1.046,1.063,1.086,1.100,1.102,1.120,1.126,1.149,1.149,1.168,1.182,1.189,1.202,1.225,1.242,1.251,1.268,1.272,1.294,1.310,1.322,1.347,1.364,1.388,1.408,1.422,1.434,1.469,1.486,1.515,1.555,1.586,1.598,1.617,1.639,1.678,1.694,1.733,1.769,1.803,1.847,1.886,1.893,1.962,2.004,2.038,2.079,2.136,2.178,2.243,2.296,2.362,2.419,2.464,2.542,2.616,2.622,2.623,2.683,2.804,2.859,2.923,2.987,3.055,3.135,3.232,3.330,3.454,3.483,3.484,3.483,3.474,3.461,3.451,3.433,3.433,3.423,3.406,3.391,3.382,3.365,3.346,3.346,3.341,3.332,3.322,3.314,3.304,3.297,3.287,3.278,3.272,3.263,3.262,3.253,3.245,3.246,3.234,3.234,3.225,3.227,3.218,3.218,3.219,3.219,3.220,3.220,3.220,3.221,3.230,3.235,3.245,3.244,3.266,3.292,3.426,4.327,4.339,4.352,4.364,4.380,4.390,4.399,4.417,4.427,4.444,4.462,4.471,4.489,4.507,4.526,4.544,4.561,4.586,4.596,4.626,4.635,4.670,4.679,4.707,4.724,4.748,4.768,4.795,4.829,4.855,4.871,4.906,4.932,4.958,4.986,5.011,5.048,5.082,5.097,5.132,5.167,5.208,5.240,5.279,5.319,5.366,5.398,5.419,5.428,5.472,5.463,5.454,5.652,6.554,6.594,6.639,6.723},Reflectance=[181]{38.000,38.000,39.000,38.000,42.000,41.000,53.000,57.000,57.000,53.000,49.000,47.000,48.000,44.000,43.000,45.000,42.000,43.000,45.000,46.000,43.000,45.000,45.000,45.000,46.000,43.000,45.000,49.000,51.000,54.000,53.000,52.000,50.000,52.000,54.000,54.000,54.000,51.000,46.000,48.000,54.000,54.000,56.000,49.000,60.000,54.000,54.000,46.000,45.000,39.000,30.000,33.000,34.000,32.000,41.000,48.000,47.000,48.000,48.000,45.000,48.000,56.000,56.000,52.000,51.000,56.000,58.000,49.000,50.000,52.000,47.000,46.000,46.000,46.000,47.000,58.000,75.000,76.000,75.000,75.000,77.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,80.000,77.000,74.000,74.000,89.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,77.000,76.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,76.000,73.000,69.000,70.000,61.000,58.000,60.000,65.000,66.000,65.000,64.000,63.000,52.000,30.000,32.000,31.000,31.000}
-63.555 LMS_LASER_2D_RIGHT LMS2 ID=4044,time=1225719875.201166,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=133,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.933,26.458,16.777,13.560,11.694,10.258,9.293,8.457,7.639,7.005,6.528,6.043,5.646,5.292,4.909,4.672,4.411,4.176,3.936,3.736,3.525,3.364,3.220,3.085,2.989,2.847,2.709,2.639,2.551,2.459,2.345,2.283,2.219,2.157,2.101,2.036,1.994,1.935,1.884,1.822,1.785,1.710,1.666,1.634,1.618,1.597,1.568,1.510,1.478,1.468,1.458,1.440,1.412,1.376,1.341,1.306,1.279,1.271,1.257,1.239,1.224,1.207,1.201,1.189,1.198,1.201,1.217,1.224,1.230,1.221,1.200,1.194,1.162,1.148,1.138,1.145,1.119,1.120,1.110,1.090,1.057,1.057,1.069,1.070,1.058,1.048,1.008,1.016,0.988,1.017},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,9.000,26.000,95.000,120.000,91.000,72.000,60.000,56.000,57.000,57.000,64.000,67.000,67.000,69.000,72.000,72.000,72.000,72.000,72.000,75.000,76.000,79.000,78.000,76.000,80.000,80.000,76.000,79.000,80.000,80.000,75.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,75.000,80.000,79.000,77.000,79.000,78.000,79.000,80.000,80.000,79.000,77.000,69.000,69.000,72.000,73.000,76.000,76.000,78.000,77.000,78.000,78.000,79.000,75.000,68.000,61.000,53.000,44.000,43.000,51.000,61.000,58.000,63.000,68.000,66.000,55.000,58.000,51.000,47.000,38.000,34.000,38.000,39.000,44.000,43.000,36.000,28.000,31.000,27.000,41.000}
-63.568 LMS_LASER_2D_LEFT LMS1 ID=4173,time=1225719875.222299,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=170,Range=[181]{1.018,1.019,1.026,1.036,1.041,1.047,1.048,1.040,1.045,1.066,1.081,1.098,1.114,1.120,1.136,1.145,1.151,1.164,1.172,1.193,1.198,1.214,1.226,1.242,1.259,1.276,1.289,1.303,1.327,1.334,1.363,1.380,1.400,1.414,1.433,1.459,1.484,1.513,1.537,1.572,1.592,1.604,1.628,1.647,1.668,1.703,1.760,1.789,1.832,1.867,1.914,1.954,1.997,2.034,2.086,2.127,2.168,2.220,2.292,2.341,2.408,2.452,2.509,2.605,2.622,2.625,2.664,2.778,2.831,2.908,2.968,3.040,3.127,3.215,3.289,3.403,3.482,3.478,3.467,3.465,3.451,3.441,3.430,3.422,3.414,3.396,3.395,3.378,3.363,3.347,3.339,3.339,3.329,3.322,3.305,3.297,3.289,3.280,3.281,3.274,3.253,3.255,3.247,3.236,3.237,3.230,3.227,3.217,3.219,3.210,3.212,3.212,3.211,3.210,3.212,3.212,3.212,3.221,3.224,3.231,3.237,3.248,3.261,3.342,3.541,4.329,4.344,4.353,4.374,4.380,4.392,4.409,4.419,4.438,4.445,4.463,4.481,4.499,4.517,4.536,4.553,4.569,4.595,4.618,4.636,4.653,4.669,4.697,4.723,4.738,4.758,4.786,4.820,4.839,4.864,4.897,4.921,4.949,4.967,5.002,5.028,5.063,5.090,5.125,5.159,5.192,5.225,5.271,5.310,5.357,5.396,5.423,5.428,5.472,5.463,5.445,5.550,6.539,6.578,6.639,6.700},Reflectance=[181]{37.000,40.000,39.000,40.000,38.000,41.000,47.000,54.000,53.000,47.000,46.000,46.000,40.000,44.000,39.000,44.000,43.000,40.000,41.000,43.000,45.000,46.000,47.000,46.000,45.000,46.000,48.000,50.000,53.000,52.000,49.000,49.000,50.000,52.000,53.000,53.000,53.000,54.000,50.000,49.000,54.000,56.000,59.000,55.000,65.000,61.000,54.000,51.000,42.000,46.000,38.000,32.000,42.000,43.000,36.000,43.000,46.000,46.000,45.000,49.000,43.000,55.000,57.000,56.000,51.000,56.000,57.000,56.000,56.000,49.000,50.000,47.000,46.000,53.000,52.000,48.000,75.000,77.000,76.000,75.000,76.000,76.000,75.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,76.000,72.000,78.000,100.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,76.000,77.000,77.000,76.000,76.000,77.000,77.000,77.000,76.000,76.000,77.000,77.000,77.000,74.000,70.000,71.000,63.000,57.000,59.000,59.000,61.000,65.000,66.000,64.000,62.000,26.000,33.000,29.000,29.000}
-63.568 LMS_LASER_2D_RIGHT LMS2 ID=4045,time=1225719875.214504,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=134,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.677,17.383,14.235,12.148,10.551,9.535,8.679,7.802,7.128,6.634,6.120,5.716,5.399,4.991,4.732,4.482,4.230,3.991,3.797,3.558,3.382,3.248,3.107,3.008,2.889,2.766,2.670,2.577,2.468,2.340,2.300,2.239,2.167,2.121,2.061,2.010,1.953,1.898,1.837,1.797,1.723,1.666,1.632,1.621,1.594,1.559,1.497,1.476,1.467,1.458,1.445,1.412,1.392,1.348,1.308,1.297,1.281,1.263,1.249,1.228,1.212,1.207,1.195,1.191,1.204,1.211,1.223,1.225,1.221,1.204,1.195,1.171,1.150,1.147,1.147,1.128,1.119,1.116,1.090,1.065,1.064,1.059,1.071,1.056,1.061,1.013,0.998,1.018,1.023},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,38.000,69.000,121.000,97.000,78.000,61.000,56.000,58.000,55.000,63.000,70.000,68.000,69.000,71.000,71.000,71.000,72.000,74.000,75.000,77.000,77.000,79.000,78.000,80.000,80.000,79.000,80.000,80.000,80.000,72.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,77.000,70.000,80.000,78.000,75.000,75.000,75.000,78.000,80.000,79.000,79.000,78.000,70.000,66.000,69.000,74.000,76.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,70.000,64.000,54.000,48.000,48.000,58.000,63.000,58.000,65.000,71.000,66.000,56.000,59.000,55.000,47.000,36.000,34.000,38.000,41.000,40.000,50.000,44.000,28.000,27.000,31.000,36.000}
-63.571 DESIRED_THRUST iJoystick 86.60237434
-63.571 DESIRED_RUDDER iJoystick 0
-63.583 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.6991,19.8330,-0.9461},Vel=[3x1]{-0.9049,-0.6525,5.3846},Raw=[2x1]{21.9602,-0.9461},time=1225719875.23047900199890,Speed=1.11562162320026,Pitch=0.04711042841061,Roll=0.02019018360455,PitchDot=0.04486707467677,RollDot=-0.00179468298707
-63.583 ODOMETRY_POSE iPlatform Pose=[3x1]{5.6991,19.8330,-0.9459},Vel=[3x1]{-0.9049,-0.6525,-0.8991},Raw=[2x1]{21.9602,-0.9461},time=1225719875.2305,Speed=1.1156,Pitch=0.0112,Roll=0.0500,PitchDot=0.0293,RollDot=0.0340
-63.582 LMS_LASER_2D_LEFT LMS1 ID=4174,time=1225719875.235630,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=171,Range=[181]{1.014,1.017,1.033,1.034,1.037,1.051,1.055,1.060,1.053,1.075,1.084,1.097,1.115,1.127,1.124,1.143,1.150,1.159,1.169,1.185,1.196,1.216,1.225,1.236,1.261,1.267,1.288,1.305,1.316,1.337,1.359,1.374,1.383,1.409,1.434,1.453,1.483,1.508,1.534,1.565,1.582,1.617,1.621,1.635,1.659,1.694,1.751,1.789,1.828,1.867,1.898,1.936,1.971,2.018,2.071,2.115,2.154,2.203,2.276,2.318,2.389,2.455,2.495,2.577,2.614,2.626,2.643,2.762,2.825,2.899,2.946,3.026,3.100,3.196,3.263,3.409,3.472,3.475,3.482,3.467,3.451,3.442,3.425,3.412,3.403,3.389,3.378,3.371,3.356,3.341,3.332,3.324,3.323,3.313,3.305,3.296,3.286,3.274,3.265,3.253,3.254,3.243,3.237,3.236,3.227,3.229,3.219,3.218,3.212,3.209,3.202,3.204,3.204,3.204,3.205,3.213,3.213,3.213,3.224,3.221,3.230,3.233,3.246,3.284,3.417,3.523,4.338,4.352,4.365,4.372,4.391,4.401,4.420,4.429,4.448,4.456,4.473,4.491,4.509,4.535,4.545,4.569,4.587,4.611,4.619,4.652,4.668,4.688,4.721,4.736,4.759,4.776,4.808,4.836,4.854,4.886,4.913,4.941,4.967,4.993,5.021,5.055,5.083,5.115,5.142,5.180,5.215,5.257,5.292,5.349,5.384,5.413,5.419,5.463,5.467,5.437,5.489,5.746,6.569,6.631,6.668},Reflectance=[181]{42.000,40.000,38.000,39.000,40.000,39.000,41.000,48.000,44.000,43.000,43.000,45.000,41.000,39.000,45.000,43.000,42.000,42.000,43.000,43.000,44.000,46.000,46.000,48.000,47.000,50.000,47.000,47.000,48.000,50.000,51.000,54.000,54.000,54.000,50.000,51.000,49.000,48.000,48.000,54.000,54.000,54.000,60.000,58.000,64.000,60.000,54.000,47.000,40.000,38.000,37.000,38.000,30.000,30.000,35.000,42.000,48.000,46.000,45.000,46.000,45.000,52.000,58.000,55.000,52.000,52.000,56.000,49.000,54.000,49.000,47.000,48.000,50.000,57.000,56.000,45.000,69.000,76.000,75.000,76.000,76.000,76.000,77.000,75.000,75.000,77.000,76.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,77.000,75.000,74.000,89.000,101.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,77.000,76.000,77.000,76.000,77.000,75.000,72.000,72.000,62.000,58.000,58.000,58.000,61.000,64.000,67.000,65.000,62.000,5.000,31.000,27.000,27.000}
-63.582 LMS_LASER_2D_RIGHT LMS2 ID=4046,time=1225719875.227842,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=135,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.812,18.246,14.929,12.612,10.831,9.721,8.854,7.999,7.240,6.723,6.192,5.813,5.485,5.130,4.782,4.560,4.273,4.056,3.836,3.627,3.419,3.285,3.150,3.036,2.916,2.781,2.688,2.596,2.502,2.379,2.318,2.255,2.185,2.121,2.061,2.019,1.959,1.908,1.847,1.796,1.741,1.684,1.642,1.629,1.613,1.569,1.527,1.486,1.479,1.470,1.437,1.421,1.391,1.349,1.321,1.307,1.285,1.257,1.242,1.224,1.212,1.208,1.195,1.192,1.197,1.206,1.219,1.223,1.220,1.205,1.196,1.187,1.169,1.161,1.145,1.129,1.119,1.121,1.110,1.081,1.063,1.058,1.061,1.042,1.030,1.047,1.005,1.029,1.026},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,55.000,17.000,124.000,103.000,82.000,64.000,57.000,57.000,54.000,62.000,70.000,68.000,68.000,70.000,70.000,69.000,72.000,74.000,74.000,76.000,77.000,80.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,75.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,77.000,72.000,80.000,79.000,75.000,78.000,76.000,74.000,77.000,78.000,78.000,75.000,70.000,66.000,70.000,76.000,77.000,78.000,75.000,76.000,76.000,77.000,78.000,77.000,72.000,66.000,56.000,50.000,52.000,50.000,65.000,65.000,63.000,58.000,55.000,55.000,59.000,55.000,52.000,47.000,36.000,37.000,41.000,35.000,30.000,28.000,38.000,27.000,34.000,39.000}
-63.594 LMS_LASER_2D_RIGHT LMS2 ID=4047,time=1225719875.241179,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=136,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.966,21.850,15.624,12.852,11.018,9.838,8.928,8.161,7.377,6.808,6.281,5.895,5.535,5.192,4.828,4.594,4.339,4.100,3.856,3.680,3.442,3.322,3.168,3.062,2.949,2.814,2.716,2.604,2.514,2.421,2.330,2.266,2.194,2.139,2.070,2.020,1.969,1.910,1.866,1.821,1.775,1.719,1.663,1.636,1.626,1.582,1.546,1.522,1.506,1.471,1.442,1.432,1.396,1.348,1.320,1.302,1.288,1.259,1.231,1.224,1.214,1.207,1.196,1.192,1.201,1.211,1.224,1.218,1.220,1.197,1.188,1.187,1.179,1.173,1.153,1.133,1.123,1.113,1.102,1.093,1.064,1.060,1.063,1.052,1.017,1.059,1.044,1.029,0.989},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,52.000,25.000,117.000,111.000,84.000,65.000,58.000,56.000,55.000,61.000,68.000,69.000,67.000,69.000,70.000,68.000,72.000,74.000,75.000,76.000,78.000,80.000,79.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,77.000,77.000,80.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,73.000,68.000,75.000,75.000,76.000,75.000,75.000,75.000,78.000,78.000,77.000,72.000,61.000,50.000,45.000,50.000,54.000,67.000,65.000,63.000,59.000,53.000,55.000,61.000,57.000,56.000,55.000,39.000,38.000,41.000,40.000,31.000,26.000,44.000,44.000,34.000,26.000}
-63.595 DESIRED_THRUST iJoystick 87.6338999603
-63.595 DESIRED_RUDDER iJoystick 0
-63.619 DESIRED_THRUST iJoystick 87.6338999603
-63.619 DESIRED_RUDDER iJoystick 0
-63.619 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.7355,19.8590,-0.9506},Vel=[3x1]{-0.9162,-0.6543,0.7692},Raw=[2x1]{22.0049,-0.9506},time=1225719875.26649522781372,Speed=1.12584328728717,Pitch=0.04935378214445,Roll=0.01570347613687,PitchDot=0.04711042841061,RollDot=-0.00114411040426
-63.619 ODOMETRY_POSE iPlatform Pose=[3x1]{5.7355,19.8590,-0.9506},Vel=[3x1]{-0.9162,-0.6543,0.7697},Raw=[2x1]{22.0049,-0.9506},time=1225719875.2665,Speed=1.1258,Pitch=0.0159,Roll=0.0493,PitchDot=0.0330,RollDot=-0.0336
-63.565 IGPS_STATUS iGPS AppErrorFlag=false,Uptime=-14475.9,MOOSName=iGPS,Publishing=IGPS_STATUS,Subscribing=
-63.606 LMS_LASER_2D_LEFT LMS1 ID=4175,time=1225719875.248971,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=172,Range=[181]{1.005,1.011,1.011,1.031,1.029,1.045,1.051,1.054,1.068,1.071,1.086,1.093,1.107,1.115,1.122,1.140,1.143,1.152,1.166,1.182,1.199,1.207,1.223,1.245,1.259,1.268,1.286,1.298,1.314,1.340,1.349,1.378,1.390,1.405,1.424,1.461,1.475,1.507,1.535,1.562,1.583,1.608,1.632,1.644,1.659,1.686,1.746,1.771,1.808,1.846,1.896,1.925,1.964,2.009,2.068,2.101,2.145,2.199,2.259,2.318,2.379,2.445,2.511,2.600,2.622,2.614,2.643,2.750,2.818,2.888,2.946,3.004,3.098,3.191,3.256,3.409,3.479,3.476,3.485,3.478,3.461,3.453,3.433,3.423,3.404,3.387,3.378,3.365,3.354,3.349,3.341,3.329,3.323,3.315,3.305,3.296,3.289,3.274,3.266,3.253,3.252,3.247,3.234,3.228,3.227,3.220,3.212,3.208,3.210,3.210,3.200,3.202,3.204,3.204,3.203,3.213,3.211,3.211,3.221,3.221,3.222,3.225,3.242,3.252,3.283,3.388,3.504,3.431,4.363,4.374,4.385,4.393,4.411,4.430,4.439,4.455,4.472,4.495,4.500,4.527,4.546,4.563,4.581,4.602,4.616,4.645,4.666,4.694,4.721,4.729,4.753,4.777,4.799,4.825,4.854,4.877,4.913,4.931,4.958,4.993,5.019,5.053,5.073,5.105,5.143,5.172,5.210,5.250,5.292,5.340,5.384,5.421,5.419,5.454,5.472,5.437,5.463,5.796,6.568,6.625,6.638},Reflectance=[181]{42.000,40.000,46.000,42.000,38.000,40.000,40.000,46.000,43.000,46.000,44.000,48.000,45.000,45.000,46.000,45.000,48.000,43.000,45.000,45.000,45.000,46.000,46.000,43.000,45.000,46.000,45.000,48.000,47.000,47.000,47.000,48.000,53.000,52.000,53.000,45.000,49.000,48.000,49.000,52.000,54.000,54.000,53.000,54.000,64.000,62.000,52.000,51.000,48.000,46.000,36.000,32.000,31.000,32.000,37.000,43.000,48.000,44.000,47.000,46.000,50.000,52.000,50.000,49.000,51.000,52.000,56.000,55.000,51.000,48.000,47.000,51.000,49.000,55.000,57.000,46.000,63.000,76.000,76.000,77.000,77.000,77.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,77.000,77.000,75.000,73.000,85.000,100.000,6.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,75.000,75.000,76.000,75.000,76.000,76.000,77.000,77.000,76.000,76.000,77.000,76.000,77.000,75.000,73.000,72.000,62.000,58.000,57.000,58.000,62.000,64.000,66.000,65.000,64.000,49.000,29.000,28.000,26.000}
-63.606 LMS_LASER_2D_RIGHT LMS2 ID=4048,time=1225719875.254515,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=137,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.039,21.910,16.002,13.190,11.251,10.028,9.093,8.321,7.475,6.857,6.391,5.963,5.569,5.246,4.872,4.628,4.395,4.126,3.814,3.658,3.506,3.345,3.191,3.062,2.967,2.813,2.723,2.598,2.527,2.460,2.346,2.275,2.228,2.163,2.095,2.037,1.969,1.910,1.858,1.821,1.786,1.740,1.670,1.643,1.625,1.588,1.551,1.525,1.500,1.473,1.456,1.435,1.396,1.350,1.323,1.304,1.271,1.251,1.244,1.227,1.219,1.205,1.195,1.193,1.203,1.215,1.222,1.224,1.225,1.216,1.204,1.187,1.182,1.173,1.156,1.137,1.127,1.111,1.116,1.097,1.055,1.064,1.070,1.068,1.062,1.019,1.036,1.038,1.017},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,15.000,29.000,110.000,115.000,88.000,67.000,58.000,54.000,56.000,60.000,65.000,67.000,67.000,69.000,70.000,68.000,72.000,73.000,78.000,75.000,78.000,79.000,78.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,76.000,76.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,77.000,72.000,72.000,72.000,70.000,72.000,70.000,73.000,73.000,77.000,77.000,77.000,73.000,58.000,42.000,43.000,48.000,48.000,53.000,63.000,64.000,60.000,56.000,56.000,59.000,54.000,55.000,50.000,40.000,32.000,40.000,44.000,44.000,37.000,28.000,35.000,40.000,32.000}
-63.618 LMS_LASER_2D_LEFT LMS1 ID=4176,time=1225719875.262311,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=173,Range=[181]{1.003,1.021,1.018,1.029,1.034,1.045,1.052,1.055,1.067,1.079,1.081,1.092,1.109,1.109,1.130,1.133,1.140,1.157,1.166,1.180,1.189,1.208,1.215,1.241,1.254,1.273,1.287,1.293,1.318,1.329,1.351,1.371,1.384,1.403,1.427,1.452,1.469,1.506,1.526,1.547,1.577,1.601,1.625,1.663,1.659,1.687,1.746,1.775,1.810,1.832,1.886,1.925,1.940,1.998,2.050,2.097,2.137,2.194,2.257,2.309,2.376,2.428,2.486,2.597,2.618,2.613,2.621,2.729,2.785,2.879,2.936,2.992,3.076,3.180,3.265,3.409,3.482,3.488,3.485,3.477,3.461,3.453,3.442,3.423,3.407,3.397,3.386,3.372,3.362,3.347,3.347,3.334,3.328,3.321,3.312,3.303,3.285,3.275,3.271,3.262,3.251,3.244,3.245,3.236,3.227,3.219,3.211,3.212,3.203,3.202,3.201,3.202,3.202,3.200,3.209,3.211,3.209,3.218,3.218,3.227,3.228,3.229,3.231,3.237,3.260,3.289,3.348,3.431,3.561,4.366,4.381,4.394,4.409,4.421,4.438,4.446,4.472,4.483,4.502,4.517,4.537,4.554,4.572,4.599,4.618,4.634,4.658,4.684,4.710,4.730,4.745,4.767,4.801,4.825,4.846,4.869,4.905,4.931,4.950,4.980,5.017,5.043,5.073,5.098,5.133,5.164,5.210,5.240,5.274,5.334,5.378,5.424,5.419,5.428,5.472,5.445,5.454,5.715,6.533,6.595,6.634},Reflectance=[181]{40.000,41.000,40.000,41.000,39.000,37.000,36.000,41.000,43.000,40.000,41.000,43.000,43.000,43.000,37.000,47.000,45.000,45.000,45.000,46.000,46.000,46.000,50.000,45.000,48.000,44.000,47.000,49.000,49.000,50.000,48.000,49.000,54.000,48.000,51.000,46.000,50.000,47.000,52.000,54.000,52.000,47.000,50.000,38.000,63.000,57.000,52.000,49.000,49.000,55.000,42.000,35.000,30.000,31.000,35.000,37.000,43.000,45.000,41.000,45.000,52.000,55.000,54.000,43.000,53.000,51.000,55.000,58.000,55.000,48.000,50.000,50.000,48.000,50.000,57.000,45.000,59.000,77.000,76.000,76.000,77.000,77.000,76.000,76.000,77.000,76.000,76.000,77.000,76.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,75.000,74.000,73.000,81.000,97.000,102.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,75.000,76.000,76.000,76.000,76.000,77.000,75.000,76.000,75.000,77.000,77.000,77.000,75.000,73.000,72.000,64.000,59.000,59.000,59.000,63.000,64.000,63.000,66.000,64.000,51.000,29.000,31.000,30.000}
-63.619 LMS_LASER_2D_RIGHT LMS2 ID=4049,time=1225719875.267851,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=138,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.959,22.080,16.350,13.445,11.506,10.143,9.195,8.416,7.556,6.912,6.442,5.999,5.605,5.265,4.935,4.663,4.422,4.151,3.802,3.628,3.512,3.354,3.188,3.077,2.989,2.852,2.731,2.613,2.535,2.461,2.372,2.276,2.230,2.165,2.086,2.037,1.977,1.927,1.872,1.832,1.797,1.752,1.706,1.660,1.634,1.586,1.560,1.535,1.507,1.479,1.455,1.428,1.396,1.367,1.346,1.321,1.277,1.264,1.253,1.226,1.207,1.202,1.194,1.187,1.196,1.209,1.215,1.218,1.228,1.224,1.202,1.188,1.187,1.168,1.160,1.139,1.128,1.112,1.098,1.107,1.062,1.060,1.066,1.053,1.062,1.017,1.041,1.023,0.985},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,5.000,101.000,119.000,88.000,71.000,59.000,54.000,56.000,60.000,64.000,67.000,68.000,70.000,70.000,70.000,73.000,73.000,80.000,73.000,77.000,76.000,77.000,79.000,80.000,79.000,80.000,80.000,81.000,81.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,75.000,74.000,71.000,64.000,60.000,69.000,74.000,72.000,72.000,76.000,76.000,77.000,75.000,65.000,50.000,45.000,46.000,42.000,48.000,62.000,65.000,59.000,54.000,54.000,56.000,55.000,55.000,53.000,42.000,33.000,39.000,38.000,32.000,35.000,26.000,34.000,30.000,26.000}
-63.631 LMS_LASER_2D_LEFT LMS1 ID=4177,time=1225719875.275651,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=174,Range=[181]{1.009,1.012,0.997,1.025,1.038,1.043,1.048,1.050,1.068,1.080,1.084,1.092,1.103,1.110,1.120,1.131,1.143,1.156,1.166,1.185,1.192,1.210,1.212,1.224,1.249,1.271,1.278,1.293,1.316,1.329,1.346,1.366,1.380,1.403,1.422,1.448,1.474,1.498,1.526,1.556,1.573,1.609,1.638,1.639,1.685,1.707,1.738,1.775,1.804,1.833,1.879,1.924,1.955,1.999,2.055,2.087,2.139,2.184,2.240,2.301,2.359,2.417,2.469,2.587,2.617,2.614,2.613,2.708,2.787,2.872,2.937,2.991,3.070,3.166,3.273,3.400,3.487,3.498,3.493,3.479,3.473,3.458,3.440,3.432,3.412,3.406,3.395,3.380,3.370,3.361,3.353,3.343,3.334,3.325,3.317,3.309,3.301,3.284,3.276,3.271,3.258,3.249,3.242,3.234,3.227,3.220,3.208,3.209,3.201,3.203,3.202,3.202,3.209,3.208,3.208,3.209,3.218,3.217,3.228,3.219,3.227,3.228,3.227,3.233,3.230,3.250,3.258,3.267,3.382,3.508,4.372,4.391,4.401,4.421,4.438,4.448,4.463,4.483,4.503,4.518,4.537,4.555,4.572,4.593,4.616,4.635,4.652,4.676,4.693,4.722,4.745,4.766,4.791,4.827,4.845,4.869,4.904,4.922,4.950,4.972,5.007,5.042,5.063,5.099,5.131,5.165,5.197,5.238,5.265,5.322,5.378,5.411,5.419,5.428,5.481,5.445,5.445,5.688,6.488,6.546,6.594},Reflectance=[181]{39.000,35.000,32.000,38.000,41.000,39.000,42.000,48.000,39.000,40.000,43.000,43.000,44.000,48.000,44.000,46.000,48.000,46.000,46.000,43.000,42.000,43.000,52.000,50.000,46.000,48.000,47.000,50.000,52.000,54.000,49.000,45.000,49.000,48.000,49.000,44.000,52.000,51.000,52.000,54.000,54.000,37.000,43.000,31.000,43.000,54.000,49.000,49.000,45.000,51.000,33.000,39.000,31.000,32.000,35.000,34.000,37.000,46.000,42.000,47.000,53.000,55.000,55.000,48.000,53.000,52.000,55.000,56.000,56.000,52.000,47.000,49.000,49.000,48.000,56.000,46.000,56.000,77.000,75.000,74.000,75.000,76.000,76.000,76.000,75.000,76.000,76.000,77.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,76.000,76.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,74.000,72.000,76.000,93.000,104.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,77.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,76.000,75.000,75.000,76.000,77.000,76.000,76.000,72.000,71.000,65.000,58.000,59.000,58.000,63.000,63.000,62.000,65.000,64.000,53.000,36.000,36.000,34.000}
-63.631 LMS_LASER_2D_RIGHT LMS2 ID=4050,time=1225719875.281185,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=139,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.711,22.085,16.558,13.585,11.626,10.187,9.248,8.462,7.586,6.972,6.450,6.017,5.622,5.284,4.954,4.672,4.422,4.164,3.911,3.683,3.510,3.353,3.189,3.077,2.979,2.855,2.731,2.633,2.557,2.457,2.338,2.278,2.228,2.148,2.087,2.036,1.979,1.935,1.875,1.822,1.785,1.748,1.701,1.662,1.634,1.597,1.562,1.536,1.500,1.470,1.448,1.428,1.397,1.369,1.346,1.309,1.286,1.271,1.258,1.226,1.215,1.207,1.196,1.193,1.191,1.204,1.211,1.215,1.226,1.221,1.211,1.192,1.173,1.164,1.160,1.147,1.134,1.117,1.110,1.102,1.065,1.052,1.058,1.062,1.070,1.013,1.012,0.999,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,15.000,8.000,96.000,117.000,88.000,72.000,59.000,54.000,57.000,58.000,64.000,67.000,67.000,70.000,70.000,71.000,72.000,75.000,74.000,74.000,76.000,72.000,75.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,79.000,77.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,72.000,68.000,74.000,72.000,66.000,63.000,69.000,76.000,75.000,72.000,75.000,78.000,77.000,77.000,70.000,63.000,54.000,48.000,45.000,47.000,54.000,61.000,60.000,56.000,50.000,45.000,50.000,54.000,51.000,43.000,36.000,37.000,41.000,40.000,39.000,27.000,25.000,26.000,25.000}
-63.643 DESIRED_THRUST iJoystick 87.6338999603
-63.643 DESIRED_RUDDER iJoystick 0
-63.642 LMS_LASER_2D_LEFT LMS1 ID=4178,time=1225719875.288988,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=175,Range=[181]{1.007,1.013,1.020,1.023,1.031,1.039,1.041,1.056,1.068,1.076,1.082,1.090,1.090,1.107,1.125,1.138,1.140,1.157,1.166,1.181,1.196,1.209,1.225,1.216,1.240,1.263,1.275,1.297,1.310,1.331,1.351,1.362,1.387,1.397,1.423,1.447,1.471,1.494,1.511,1.548,1.577,1.615,1.629,1.660,1.668,1.726,1.743,1.777,1.805,1.837,1.881,1.925,1.944,1.998,2.041,2.094,2.146,2.180,2.236,2.307,2.345,2.409,2.479,2.575,2.613,2.612,2.621,2.700,2.799,2.866,2.927,2.993,3.057,3.162,3.267,3.394,3.483,3.497,3.501,3.475,3.471,3.457,3.441,3.433,3.414,3.406,3.399,3.388,3.372,3.363,3.356,3.347,3.341,3.329,3.321,3.311,3.309,3.300,3.291,3.281,3.272,3.264,3.258,3.239,3.231,3.234,3.223,3.207,3.208,3.207,3.208,3.207,3.214,3.213,3.223,3.224,3.225,3.234,3.226,3.227,3.235,3.226,3.219,3.217,3.218,3.227,3.233,3.236,3.260,3.366,3.456,4.381,4.412,4.421,4.439,4.448,4.464,4.483,4.492,4.518,4.535,4.546,4.573,4.591,4.614,4.633,4.651,4.677,4.695,4.722,4.746,4.767,4.790,4.816,4.844,4.870,4.898,4.921,4.951,4.973,5.008,5.034,5.074,5.097,5.133,5.164,5.197,5.234,5.266,5.317,5.367,5.411,5.419,5.428,5.463,5.454,5.445,5.691,6.446,6.503,6.534},Reflectance=[181]{38.000,41.000,37.000,36.000,42.000,42.000,43.000,46.000,43.000,39.000,42.000,45.000,46.000,46.000,42.000,40.000,45.000,45.000,45.000,41.000,44.000,42.000,45.000,54.000,53.000,48.000,49.000,47.000,50.000,51.000,48.000,49.000,48.000,52.000,53.000,48.000,51.000,50.000,53.000,54.000,52.000,40.000,48.000,36.000,28.000,45.000,51.000,45.000,42.000,44.000,37.000,35.000,32.000,33.000,32.000,40.000,44.000,48.000,44.000,46.000,54.000,55.000,55.000,54.000,55.000,51.000,55.000,57.000,54.000,53.000,50.000,53.000,51.000,46.000,54.000,48.000,55.000,74.000,72.000,68.000,72.000,75.000,76.000,76.000,76.000,76.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,76.000,75.000,75.000,75.000,76.000,76.000,76.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,78.000,75.000,74.000,75.000,74.000,94.000,105.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,76.000,75.000,76.000,76.000,76.000,77.000,76.000,77.000,76.000,76.000,75.000,77.000,76.000,77.000,75.000,72.000,70.000,67.000,60.000,58.000,58.000,62.000,63.000,66.000,64.000,63.000,58.000,45.000,43.000,39.000}
-63.642 LMS_LASER_2D_RIGHT LMS2 ID=4051,time=1225719875.294517,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=140,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.271,16.547,13.569,11.635,10.188,9.255,8.463,7.578,6.982,6.457,5.999,5.613,5.264,4.962,4.689,4.422,4.160,3.919,3.717,3.511,3.367,3.208,3.075,2.971,2.842,2.723,2.633,2.558,2.459,2.297,2.260,2.233,2.147,2.078,2.024,1.969,1.927,1.875,1.829,1.782,1.751,1.692,1.660,1.633,1.588,1.561,1.535,1.508,1.478,1.448,1.422,1.396,1.369,1.332,1.314,1.281,1.274,1.255,1.240,1.222,1.208,1.198,1.192,1.190,1.199,1.202,1.216,1.213,1.222,1.224,1.190,1.173,1.169,1.164,1.141,1.121,1.115,1.114,1.101,1.061,1.061,1.057,1.059,1.064,1.049,1.047,0.989,0.986},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,8.000,98.000,119.000,90.000,72.000,58.000,55.000,58.000,59.000,64.000,67.000,67.000,68.000,69.000,72.000,73.000,74.000,74.000,74.000,77.000,75.000,75.000,78.000,79.000,81.000,80.000,80.000,77.000,80.000,82.000,82.000,79.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,76.000,77.000,77.000,78.000,78.000,79.000,78.000,79.000,78.000,77.000,72.000,72.000,76.000,74.000,71.000,71.000,74.000,77.000,74.000,75.000,77.000,78.000,78.000,76.000,68.000,60.000,54.000,45.000,48.000,43.000,39.000,56.000,60.000,54.000,48.000,50.000,56.000,57.000,48.000,47.000,35.000,37.000,41.000,39.000,38.000,50.000,46.000,26.000,27.000}
-63.655 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.7717,19.8849,-0.9525},Vel=[3x1]{-0.9008,-0.6407,-6.2821},Raw=[2x1]{22.0494,-0.9525},time=1225719875.30246329307556,Speed=1.10539995911334,Pitch=0.04935378214445,Roll=0.01121676866919,PitchDot=0.02467689107222,RollDot=-0.00026920244806
-63.655 ODOMETRY_POSE iPlatform Pose=[3x1]{5.7717,19.8849,-0.9527},Vel=[3x1]{-0.9008,-0.6407,0.0011},Raw=[2x1]{22.0494,-0.9525},time=1225719875.3025,Speed=1.1054,Pitch=0.0195,Roll=0.0467,PitchDot=0.0247,RollDot=-0.0003
-63.667 DESIRED_THRUST iJoystick 87.6338999603
-63.667 DESIRED_RUDDER iJoystick 0
-63.654 LMS_LASER_2D_LEFT LMS1 ID=4179,time=1225719875.302324,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=176,Range=[181]{1.007,1.010,1.013,1.025,1.038,1.042,1.052,1.065,1.065,1.084,1.084,1.086,1.107,1.110,1.122,1.127,1.148,1.153,1.168,1.184,1.190,1.208,1.225,1.238,1.246,1.264,1.281,1.291,1.307,1.333,1.346,1.365,1.384,1.404,1.426,1.448,1.473,1.495,1.505,1.526,1.557,1.597,1.632,1.648,1.699,1.726,1.740,1.774,1.805,1.848,1.864,1.902,1.949,2.006,2.043,2.085,2.138,2.183,2.251,2.299,2.337,2.402,2.480,2.557,2.617,2.609,2.623,2.695,2.803,2.861,2.917,2.992,3.045,3.157,3.267,3.395,3.481,3.497,3.506,3.498,3.469,3.466,3.457,3.436,3.427,3.408,3.397,3.381,3.374,3.363,3.358,3.341,3.342,3.330,3.321,3.319,3.310,3.302,3.292,3.291,3.281,3.271,3.264,3.256,3.247,3.238,3.230,3.222,3.208,3.205,3.217,3.215,3.219,3.228,3.228,3.232,3.234,3.239,3.240,3.235,3.237,3.235,3.228,3.219,3.221,3.222,3.221,3.220,3.233,3.253,3.340,3.424,3.555,4.419,4.428,4.446,4.463,4.482,4.494,4.516,4.535,4.553,4.572,4.592,4.615,4.636,4.652,4.678,4.696,4.720,4.746,4.766,4.791,4.817,4.844,4.869,4.895,4.922,4.953,4.974,5.008,5.035,5.063,5.097,5.132,5.164,5.203,5.233,5.259,5.310,5.357,5.404,5.417,5.437,5.462,5.445,5.454,5.697,6.424,6.491,6.543},Reflectance=[181]{43.000,40.000,41.000,43.000,41.000,38.000,44.000,42.000,42.000,43.000,43.000,44.000,42.000,43.000,41.000,43.000,45.000,44.000,47.000,42.000,45.000,45.000,45.000,52.000,48.000,44.000,48.000,49.000,48.000,38.000,46.000,50.000,46.000,52.000,50.000,49.000,52.000,54.000,58.000,56.000,54.000,53.000,53.000,48.000,38.000,45.000,53.000,49.000,42.000,38.000,31.000,30.000,29.000,31.000,32.000,33.000,44.000,46.000,43.000,46.000,59.000,56.000,56.000,54.000,53.000,49.000,56.000,59.000,52.000,51.000,50.000,53.000,53.000,48.000,54.000,48.000,50.000,65.000,57.000,58.000,66.000,73.000,75.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,77.000,76.000,76.000,75.000,75.000,75.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,77.000,75.000,75.000,75.000,77.000,77.000,76.000,76.000,77.000,78.000,77.000,78.000,78.000,79.000,76.000,76.000,76.000,74.000,77.000,94.000,106.000,105.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,76.000,76.000,76.000,76.000,76.000,78.000,76.000,76.000,76.000,76.000,76.000,76.000,75.000,72.000,70.000,67.000,62.000,57.000,58.000,60.000,61.000,66.000,65.000,63.000,61.000,59.000,57.000,54.000}
-63.654 LMS_LASER_2D_RIGHT LMS2 ID=4052,time=1225719875.307848,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=141,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.275,-1.000,16.272,13.425,11.475,10.117,9.187,8.407,7.541,6.934,6.417,5.973,5.596,5.237,4.936,4.681,4.412,4.151,3.933,3.715,3.511,3.368,3.194,3.072,2.949,2.847,2.732,2.631,2.542,2.441,2.278,2.266,2.225,2.147,2.071,2.008,1.963,1.918,1.867,1.832,1.794,1.747,1.696,1.659,1.623,1.595,1.555,1.517,1.497,1.477,1.440,1.420,1.400,1.377,1.324,1.310,1.289,1.272,1.257,1.227,1.212,1.206,1.197,1.193,1.197,1.194,1.200,1.207,1.209,1.221,1.226,1.210,1.196,1.177,1.147,1.113,1.108,1.113,1.118,1.101,1.069,1.053,1.055,1.067,1.065,1.056,1.044,1.022,0.999},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,13.000,0.000,106.000,118.000,90.000,71.000,59.000,54.000,58.000,58.000,65.000,68.000,68.000,67.000,70.000,72.000,73.000,74.000,75.000,77.000,77.000,78.000,79.000,78.000,78.000,80.000,80.000,80.000,80.000,80.000,82.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,74.000,72.000,75.000,75.000,70.000,73.000,75.000,76.000,77.000,75.000,73.000,77.000,78.000,78.000,74.000,66.000,62.000,61.000,52.000,50.000,41.000,42.000,42.000,48.000,51.000,56.000,60.000,61.000,56.000,47.000,41.000,37.000,35.000,40.000,43.000,38.000,46.000,40.000,31.000,29.000}
-63.666 LMS_LASER_2D_LEFT LMS1 ID=4180,time=1225719875.315659,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=177,Range=[181]{1.010,1.017,1.016,1.035,1.034,1.039,1.056,1.059,1.068,1.076,1.079,1.092,1.101,1.111,1.123,1.132,1.140,1.149,1.170,1.185,1.190,1.212,1.224,1.237,1.251,1.269,1.275,1.301,1.310,1.333,1.348,1.364,1.384,1.406,1.426,1.451,1.476,1.495,1.502,1.520,1.543,1.584,1.625,1.653,1.688,1.715,1.750,1.776,1.817,1.853,1.873,1.933,1.941,1.995,2.044,2.096,2.148,2.197,2.240,2.313,2.332,2.422,2.498,2.552,2.617,2.612,2.636,2.715,2.824,2.865,2.940,3.001,3.037,3.176,3.276,3.423,3.499,3.531,3.535,3.525,3.497,3.470,3.462,3.447,3.430,3.418,3.399,3.390,3.384,3.364,3.356,3.350,3.340,3.338,3.332,3.322,3.319,3.309,3.302,3.293,3.284,3.283,3.273,3.265,3.254,3.246,3.238,3.228,3.220,3.219,3.214,3.228,3.237,3.237,3.237,3.248,3.239,3.249,3.243,3.242,3.243,3.231,3.224,3.219,3.219,3.221,3.208,3.213,3.216,3.223,3.262,3.325,3.386,3.434,3.461,4.445,4.475,4.491,4.502,4.517,4.536,4.551,4.573,4.590,4.623,4.640,4.659,4.688,4.703,4.720,4.744,4.773,4.792,4.826,4.852,4.877,4.902,4.931,4.950,4.972,5.007,5.045,5.075,5.097,5.132,5.168,5.200,5.234,5.267,5.310,5.359,5.404,5.424,5.445,5.472,5.445,5.454,5.765,6.411,6.471,6.537},Reflectance=[181]{37.000,40.000,43.000,44.000,40.000,42.000,45.000,43.000,39.000,43.000,46.000,47.000,43.000,44.000,45.000,46.000,46.000,46.000,48.000,43.000,46.000,44.000,45.000,43.000,46.000,47.000,50.000,49.000,50.000,43.000,46.000,50.000,50.000,49.000,50.000,50.000,50.000,54.000,62.000,63.000,60.000,55.000,54.000,54.000,50.000,53.000,50.000,46.000,39.000,39.000,31.000,37.000,29.000,30.000,31.000,33.000,41.000,43.000,46.000,48.000,56.000,53.000,56.000,56.000,53.000,51.000,56.000,56.000,53.000,52.000,49.000,50.000,57.000,48.000,50.000,49.000,50.000,55.000,53.000,53.000,57.000,67.000,75.000,75.000,75.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,76.000,76.000,77.000,76.000,76.000,76.000,76.000,76.000,75.000,75.000,76.000,75.000,76.000,75.000,77.000,75.000,75.000,75.000,75.000,76.000,76.000,76.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,76.000,77.000,76.000,75.000,74.000,81.000,95.000,105.000,108.000,108.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,75.000,76.000,75.000,76.000,75.000,75.000,76.000,77.000,76.000,75.000,76.000,77.000,76.000,76.000,74.000,71.000,70.000,67.000,64.000,58.000,58.000,59.000,61.000,63.000,64.000,62.000,72.000,62.000,62.000,59.000}
-63.679 LMS_LASER_2D_LEFT LMS1 ID=4181,time=1225719875.328993,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=178,Range=[181]{1.008,1.018,1.015,1.029,1.039,1.045,1.046,1.061,1.067,1.067,1.086,1.090,1.104,1.116,1.132,1.134,1.138,1.150,1.174,1.183,1.199,1.216,1.225,1.241,1.250,1.264,1.280,1.296,1.316,1.332,1.347,1.373,1.389,1.412,1.436,1.455,1.481,1.498,1.502,1.528,1.546,1.581,1.625,1.666,1.700,1.721,1.745,1.785,1.823,1.860,1.885,1.926,1.958,2.005,2.054,2.099,2.169,2.205,2.259,2.323,2.362,2.436,2.500,2.584,2.614,2.613,2.635,2.759,2.828,2.887,2.956,3.019,3.088,3.182,3.303,3.427,3.529,3.554,3.554,3.545,3.545,3.530,3.481,3.465,3.445,3.430,3.408,3.401,3.390,3.377,3.373,3.359,3.357,3.348,3.339,3.329,3.329,3.320,3.310,3.300,3.292,3.282,3.273,3.264,3.264,3.247,3.245,3.237,3.229,3.229,3.240,3.229,3.238,3.237,3.246,3.257,3.248,3.250,3.256,3.246,3.252,3.241,3.234,3.225,3.216,3.215,3.207,3.204,3.209,3.215,3.215,3.239,3.307,3.309,3.337,3.249,4.475,4.493,4.503,4.526,4.536,4.563,4.573,4.597,4.623,4.641,4.669,4.686,4.705,4.731,4.752,4.774,4.801,4.827,4.851,4.878,4.903,4.933,4.958,4.983,5.021,5.045,5.082,5.107,5.141,5.177,5.212,5.246,5.279,5.319,5.355,5.401,5.420,5.453,5.479,5.445,5.472,5.865,6.393,6.454,6.524},Reflectance=[181]{38.000,36.000,42.000,41.000,42.000,46.000,46.000,44.000,48.000,48.000,44.000,45.000,44.000,42.000,45.000,47.000,46.000,47.000,45.000,47.000,45.000,45.000,45.000,46.000,50.000,52.000,48.000,51.000,52.000,47.000,50.000,49.000,49.000,48.000,47.000,48.000,48.000,55.000,66.000,63.000,63.000,57.000,54.000,52.000,51.000,52.000,48.000,46.000,35.000,38.000,38.000,34.000,29.000,30.000,32.000,33.000,38.000,42.000,47.000,49.000,54.000,56.000,53.000,54.000,52.000,51.000,56.000,52.000,51.000,51.000,48.000,49.000,49.000,47.000,50.000,50.000,50.000,53.000,49.000,57.000,67.000,70.000,70.000,73.000,75.000,75.000,77.000,77.000,77.000,76.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,76.000,76.000,76.000,75.000,75.000,76.000,75.000,75.000,76.000,76.000,76.000,76.000,76.000,75.000,75.000,76.000,76.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,74.000,74.000,78.000,95.000,97.000,106.000,17.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,78.000,77.000,78.000,78.000,77.000,76.000,76.000,76.000,75.000,76.000,76.000,77.000,77.000,76.000,77.000,76.000,77.000,77.000,76.000,74.000,71.000,71.000,68.000,66.000,62.000,61.000,57.000,61.000,60.000,63.000,61.000,78.000,66.000,64.000,63.000}
-63.679 LMS_LASER_2D_RIGHT LMS2 ID=4053,time=1225719875.321190,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=142,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.504,-1.000,15.873,13.121,11.217,9.978,9.034,8.278,7.474,6.837,6.366,5.937,5.536,5.211,4.899,4.622,4.366,4.135,3.899,3.697,3.471,3.343,3.189,3.050,2.949,2.849,2.722,2.615,2.527,2.420,2.305,2.274,2.227,2.124,2.051,2.010,1.969,1.915,1.858,1.832,1.782,1.730,1.679,1.653,1.613,1.556,1.527,1.519,1.499,1.466,1.444,1.428,1.397,1.359,1.315,1.306,1.292,1.271,1.248,1.223,1.210,1.201,1.197,1.191,1.191,1.189,1.204,1.208,1.221,1.217,1.217,1.208,1.197,1.177,1.152,1.107,1.092,1.094,1.095,1.099,1.069,1.052,1.052,1.058,1.054,1.034,1.037,1.016,0.996},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,8.000,0.000,108.000,116.000,85.000,66.000,59.000,54.000,56.000,58.000,64.000,66.000,69.000,70.000,70.000,71.000,71.000,74.000,75.000,76.000,76.000,78.000,77.000,79.000,80.000,81.000,80.000,81.000,81.000,79.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,78.000,78.000,79.000,79.000,78.000,74.000,72.000,79.000,78.000,76.000,78.000,78.000,74.000,71.000,73.000,76.000,77.000,76.000,75.000,75.000,76.000,76.000,75.000,71.000,70.000,66.000,55.000,49.000,43.000,37.000,42.000,49.000,48.000,47.000,51.000,61.000,62.000,64.000,59.000,50.000,35.000,37.000,39.000,43.000,35.000,30.000,31.000,31.000,28.000}
-63.691 DESIRED_THRUST iJoystick 87.6338999603
-63.691 DESIRED_RUDDER iJoystick 0
-63.691 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.7976,19.9033,-0.9525},Vel=[3x1]{-0.8698,-0.6187,-4.8718},Raw=[2x1]{22.0813,-0.9525},time=1225719875.33848929405212,Speed=1.06743377821909,Pitch=0.05159713587829,Roll=0.01121676866919,PitchDot=0.01570347613687,RollDot=0.00020190183605
-63.691 ODOMETRY_POSE iPlatform Pose=[3x1]{5.7976,19.9033,-0.9527},Vel=[3x1]{-0.8698,-0.6187,1.4114},Raw=[2x1]{22.0813,-0.9525},time=1225719875.3385,Speed=1.0674,Pitch=0.0208,Roll=0.0485,PitchDot=0.0027,RollDot=-0.0155
-63.691 VEHICLE_GEOMETRY iPlatform Name=LISA, Sensor_0=LMS_LASER_2D, Pose3D_0=[4x1]{0.0000,0.3500,0.0000,0.0000},SHAPE_2D=[2x8]{0.3300,0.3300,0.2100,0.2100,-0.2100,-0.2100,-0.3300,-0.3300,-0.4100,0.4100,0.4100,0.5700,0.5700,0.4100,0.4100,-0.4100,}
-63.319 RELAYBOX_STATUS iRelayBox LADYBUG is OFF,LMS1 is ON,LMS2 is ON,P10 is OFF,P11 is OFF,P12 is OFF,P13 is OFF,P14 is OFF,P15 is OFF,P16 is OFF,P5 is OFF,P6 is OFF,P7 is OFF,P8 is OFF,P9 is OFF,PANTILT is ON,
-63.690 LMS_LASER_2D_LEFT LMS1 ID=4182,time=1225719875.342325,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=179,Range=[181]{1.009,1.013,1.027,1.031,1.040,1.050,1.056,1.064,1.073,1.077,1.089,1.092,1.107,1.124,1.132,1.141,1.148,1.167,1.181,1.185,1.208,1.216,1.225,1.242,1.252,1.266,1.283,1.304,1.317,1.337,1.351,1.376,1.396,1.417,1.441,1.461,1.488,1.513,1.538,1.552,1.569,1.593,1.634,1.675,1.702,1.722,1.759,1.792,1.819,1.869,1.899,1.947,1.965,2.010,2.070,2.107,2.169,2.224,2.273,2.323,2.382,2.446,2.516,2.578,2.612,2.612,2.658,2.778,2.842,2.900,2.963,3.030,3.105,3.206,3.333,3.443,3.545,3.586,3.600,3.601,3.598,3.577,3.552,3.512,3.485,3.451,3.438,3.413,3.402,3.394,3.379,3.388,3.412,3.429,3.409,3.404,3.387,3.377,3.340,3.319,3.299,3.291,3.281,3.274,3.265,3.255,3.255,3.243,3.246,3.238,3.246,3.246,3.255,3.255,3.265,3.284,3.281,3.262,3.255,3.257,3.244,3.245,3.234,3.225,3.217,3.207,3.207,3.205,3.201,3.201,3.207,3.206,3.206,3.206,3.302,3.229,4.476,4.494,4.500,4.527,4.548,4.564,4.583,4.606,4.632,4.651,4.667,4.685,4.712,4.732,4.759,4.783,4.807,4.836,4.860,4.887,4.910,4.935,4.966,4.990,5.018,5.054,5.081,5.116,5.150,5.181,5.221,5.251,5.290,5.319,5.365,5.417,5.420,5.470,5.479,5.445,5.507,6.296,6.388,6.454,6.516},Reflectance=[181]{39.000,45.000,37.000,38.000,42.000,43.000,45.000,45.000,45.000,48.000,46.000,47.000,42.000,42.000,45.000,42.000,45.000,42.000,45.000,43.000,45.000,45.000,46.000,46.000,51.000,49.000,49.000,50.000,49.000,50.000,52.000,51.000,48.000,50.000,46.000,46.000,47.000,54.000,54.000,56.000,60.000,55.000,54.000,43.000,48.000,49.000,41.000,34.000,32.000,36.000,34.000,36.000,30.000,30.000,34.000,33.000,42.000,43.000,44.000,49.000,51.000,56.000,56.000,55.000,51.000,54.000,54.000,56.000,50.000,50.000,48.000,50.000,49.000,46.000,52.000,53.000,53.000,55.000,58.000,70.000,77.000,76.000,74.000,76.000,79.000,76.000,78.000,76.000,75.000,75.000,76.000,79.000,85.000,88.000,87.000,88.000,88.000,88.000,81.000,79.000,76.000,76.000,75.000,76.000,76.000,75.000,75.000,75.000,75.000,76.000,75.000,75.000,75.000,75.000,76.000,79.000,78.000,77.000,78.000,79.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,75.000,75.000,75.000,74.000,74.000,77.000,99.000,27.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,76.000,76.000,75.000,76.000,75.000,76.000,75.000,77.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,73.000,72.000,70.000,68.000,66.000,64.000,60.000,57.000,60.000,60.000,62.000,66.000,69.000,67.000,66.000,64.000}
-63.690 LMS_LASER_2D_RIGHT LMS2 ID=4054,time=1225719875.334530,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=143,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.367,21.989,15.003,12.763,10.932,9.785,8.891,8.142,7.354,6.736,6.270,5.822,5.494,5.147,4.817,4.560,4.300,4.091,3.879,3.658,3.453,3.302,3.156,3.048,2.941,2.809,2.703,2.606,2.488,2.398,2.320,2.283,2.212,2.139,2.050,2.002,1.969,1.901,1.856,1.812,1.770,1.722,1.670,1.639,1.581,1.549,1.530,1.510,1.489,1.450,1.446,1.428,1.379,1.351,1.325,1.310,1.290,1.262,1.238,1.218,1.210,1.195,1.192,1.191,1.197,1.195,1.203,1.205,1.219,1.221,1.212,1.203,1.190,1.176,1.146,1.139,1.104,1.079,1.077,1.084,1.070,1.049,1.051,1.059,1.055,1.045,1.031,1.028,1.032},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,19.000,6.000,131.000,106.000,84.000,65.000,58.000,55.000,56.000,60.000,65.000,67.000,68.000,70.000,71.000,70.000,72.000,74.000,75.000,75.000,78.000,79.000,76.000,78.000,80.000,81.000,80.000,81.000,81.000,80.000,81.000,78.000,78.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,77.000,78.000,79.000,78.000,74.000,64.000,77.000,79.000,78.000,77.000,78.000,78.000,74.000,74.000,77.000,78.000,77.000,76.000,74.000,74.000,74.000,74.000,71.000,70.000,67.000,64.000,58.000,51.000,42.000,38.000,38.000,47.000,53.000,54.000,55.000,56.000,60.000,66.000,63.000,50.000,35.000,38.000,41.000,44.000,45.000,52.000,57.000,52.000,43.000}
-63.702 LMS_LASER_2D_RIGHT LMS2 ID=4055,time=1225719875.347868,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=144,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.056,18.028,14.639,12.488,10.743,9.455,8.738,7.946,7.261,6.676,6.208,5.742,5.415,5.068,4.749,4.475,4.247,4.049,3.815,3.625,3.416,3.253,3.131,3.021,2.925,2.780,2.669,2.572,2.470,2.389,2.310,2.255,2.183,2.103,2.027,1.989,1.961,1.890,1.839,1.803,1.749,1.716,1.666,1.623,1.568,1.542,1.533,1.510,1.483,1.455,1.434,1.416,1.379,1.352,1.308,1.295,1.270,1.248,1.236,1.229,1.212,1.209,1.199,1.205,1.197,1.201,1.208,1.224,1.221,1.218,1.210,1.192,1.176,1.142,1.121,1.119,1.111,1.098,1.097,1.090,1.065,1.043,1.045,1.053,1.042,1.040,1.034,1.026,1.014},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,30.000,41.000,124.000,97.000,79.000,69.000,54.000,57.000,56.000,62.000,66.000,68.000,68.000,70.000,71.000,74.000,73.000,75.000,75.000,76.000,76.000,78.000,77.000,81.000,81.000,81.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,76.000,68.000,68.000,78.000,79.000,79.000,76.000,77.000,74.000,73.000,74.000,74.000,75.000,72.000,75.000,77.000,74.000,74.000,72.000,70.000,64.000,66.000,61.000,49.000,39.000,38.000,37.000,38.000,50.000,54.000,58.000,60.000,63.000,63.000,61.000,56.000,50.000,36.000,36.000,45.000,48.000,54.000,57.000,54.000,51.000,31.000}
-63.715 LMS_LASER_2D_RIGHT LMS2 ID=4056,time=1225719875.361207,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=145,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.224,14.062,11.963,10.463,9.327,8.572,7.769,7.089,6.562,6.071,5.655,5.311,4.998,4.664,4.430,4.204,3.965,3.769,3.537,3.372,3.238,3.106,2.994,2.875,2.723,2.662,2.562,2.451,2.372,2.300,2.246,2.162,2.095,2.027,1.981,1.953,1.871,1.829,1.783,1.738,1.687,1.651,1.610,1.559,1.535,1.527,1.498,1.470,1.448,1.421,1.404,1.377,1.333,1.302,1.300,1.269,1.251,1.228,1.227,1.208,1.199,1.192,1.191,1.199,1.204,1.208,1.219,1.218,1.228,1.202,1.180,1.163,1.132,1.128,1.106,1.104,1.094,1.093,1.080,1.066,1.035,1.038,1.049,1.043,1.013,1.048,0.996,0.981},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,70.000,117.000,94.000,74.000,64.000,56.000,56.000,57.000,64.000,66.000,68.000,69.000,69.000,72.000,73.000,74.000,77.000,77.000,75.000,76.000,79.000,80.000,81.000,81.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,81.000,80.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,67.000,72.000,79.000,78.000,78.000,76.000,70.000,71.000,70.000,73.000,75.000,75.000,71.000,70.000,74.000,72.000,70.000,70.000,72.000,70.000,60.000,55.000,42.000,40.000,37.000,42.000,50.000,52.000,56.000,61.000,63.000,69.000,66.000,64.000,54.000,49.000,36.000,31.000,32.000,38.000,35.000,29.000,38.000,27.000,25.000}
-63.715 DESIRED_THRUST iJoystick 87.6338999603
-63.715 DESIRED_RUDDER iJoystick 0
-63.727 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.8334,19.9288,-0.9502},Vel=[3x1]{-0.8767,-0.6267,-6.9231},Raw=[2x1]{22.1252,-0.9502},time=1225719875.37476611137390,Speed=1.07765544230601,Pitch=0.04935378214445,Roll=0.01570347613687,PitchDot=-0.01346012240303,RollDot=0.00150304700167
-63.727 ODOMETRY_POSE iPlatform Pose=[3x1]{5.8334,19.9288,-0.9502},Vel=[3x1]{-0.8767,-0.6267,-0.6400},Raw=[2x1]{22.1252,-0.9502},time=1225719875.3748,Speed=1.0777,Pitch=0.0159,Roll=0.0493,PitchDot=-0.0117,RollDot=-0.0068
-63.715 LMS_LASER_2D_LEFT LMS1 ID=4183,time=1225719875.355669,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=180,Range=[181]{0.997,1.018,1.026,1.030,1.033,1.049,1.060,1.057,1.073,1.078,1.084,1.094,1.107,1.126,1.132,1.144,1.148,1.174,1.174,1.196,1.210,1.221,1.228,1.251,1.259,1.274,1.288,1.307,1.322,1.345,1.361,1.379,1.392,1.419,1.443,1.461,1.486,1.511,1.530,1.556,1.592,1.615,1.648,1.686,1.707,1.732,1.776,1.799,1.837,1.866,1.895,1.930,1.977,2.021,2.074,2.133,2.184,2.227,2.292,2.344,2.403,2.464,2.565,2.611,2.622,2.613,2.664,2.783,2.866,2.923,2.980,3.040,3.129,3.232,3.370,3.490,3.571,3.632,3.653,3.670,3.818,3.902,3.609,3.583,3.526,3.492,3.479,3.462,3.455,3.448,3.443,3.453,3.492,3.523,3.497,3.482,3.453,3.434,3.415,3.386,3.378,3.367,3.322,3.301,3.277,3.271,3.261,3.246,3.247,3.247,3.255,3.264,3.290,3.345,3.350,3.363,3.338,3.283,3.266,3.257,3.244,3.243,3.237,3.227,3.218,3.208,3.208,3.199,3.198,3.195,3.200,3.201,3.200,3.193,3.291,3.504,4.482,4.494,4.509,4.535,4.547,4.573,4.590,4.616,4.642,4.658,4.685,4.695,4.722,4.739,4.766,4.792,4.817,4.843,4.869,4.895,4.921,4.944,4.967,5.001,5.028,5.064,5.091,5.124,5.157,5.186,5.232,5.255,5.301,5.329,5.373,5.425,5.430,5.481,5.472,5.445,5.592,6.325,6.392,6.449,6.516},Reflectance=[181]{33.000,40.000,39.000,45.000,43.000,42.000,44.000,47.000,45.000,49.000,43.000,48.000,46.000,43.000,42.000,43.000,46.000,45.000,46.000,44.000,43.000,44.000,48.000,46.000,46.000,49.000,47.000,48.000,51.000,49.000,48.000,48.000,50.000,47.000,46.000,50.000,54.000,53.000,54.000,54.000,54.000,53.000,52.000,40.000,50.000,50.000,39.000,35.000,40.000,34.000,31.000,31.000,32.000,30.000,31.000,45.000,41.000,44.000,42.000,46.000,49.000,56.000,46.000,54.000,51.000,55.000,57.000,51.000,49.000,49.000,48.000,51.000,47.000,46.000,53.000,46.000,53.000,60.000,67.000,80.000,80.000,75.000,77.000,77.000,81.000,80.000,81.000,79.000,79.000,80.000,81.000,84.000,85.000,90.000,87.000,88.000,90.000,92.000,92.000,91.000,91.000,87.000,81.000,78.000,77.000,75.000,75.000,75.000,76.000,76.000,75.000,75.000,80.000,89.000,91.000,89.000,86.000,79.000,78.000,79.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,75.000,75.000,75.000,75.000,97.000,108.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,76.000,76.000,76.000,75.000,76.000,76.000,76.000,78.000,77.000,76.000,76.000,77.000,77.000,77.000,76.000,72.000,72.000,69.000,69.000,67.000,65.000,59.000,58.000,58.000,61.000,61.000,68.000,69.000,69.000,67.000,65.000}
-63.727 LMS_LASER_2D_LEFT LMS1 ID=4184,time=1225719875.369010,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=181,Range=[181]{1.021,1.018,1.034,1.041,1.039,1.054,1.063,1.070,1.077,1.081,1.089,1.096,1.118,1.119,1.132,1.140,1.156,1.174,1.179,1.190,1.208,1.223,1.236,1.256,1.271,1.280,1.294,1.313,1.332,1.346,1.370,1.382,1.404,1.426,1.447,1.473,1.494,1.525,1.557,1.573,1.599,1.616,1.657,1.689,1.711,1.742,1.783,1.818,1.842,1.889,1.898,1.948,1.980,2.043,2.089,2.142,2.193,2.249,2.294,2.364,2.428,2.491,2.582,2.615,2.615,2.613,2.699,2.804,2.874,2.941,2.991,3.055,3.156,3.268,3.388,3.509,3.620,3.698,3.894,3.871,3.924,3.930,3.952,3.842,3.728,3.542,3.565,3.509,3.517,3.523,3.512,3.620,4.087,4.093,4.102,4.117,4.112,3.589,3.544,3.480,3.436,3.409,3.390,3.374,3.366,3.348,3.339,3.316,3.312,3.344,3.348,3.352,3.368,3.396,3.440,3.443,3.386,3.362,3.300,3.260,3.252,3.245,3.236,3.229,3.220,3.209,3.209,3.201,3.198,3.195,3.196,3.193,3.193,3.187,3.282,3.241,4.483,4.504,4.518,4.539,4.556,4.573,4.599,4.624,4.650,4.668,4.685,4.704,4.723,4.745,4.776,4.801,4.826,4.852,4.879,4.903,4.925,4.951,4.975,5.010,5.046,5.073,5.097,5.132,5.166,5.202,5.238,5.276,5.314,5.347,5.383,5.422,5.432,5.481,5.454,5.452,5.744,6.329,6.386,6.450,6.507},Reflectance=[181]{37.000,40.000,39.000,38.000,42.000,41.000,41.000,44.000,44.000,46.000,46.000,46.000,43.000,48.000,46.000,45.000,41.000,45.000,44.000,46.000,46.000,41.000,43.000,44.000,43.000,48.000,50.000,51.000,51.000,49.000,48.000,49.000,48.000,46.000,48.000,52.000,53.000,52.000,54.000,54.000,54.000,54.000,52.000,50.000,48.000,46.000,40.000,39.000,38.000,37.000,31.000,31.000,29.000,32.000,34.000,46.000,41.000,45.000,47.000,43.000,48.000,49.000,46.000,52.000,52.000,55.000,56.000,56.000,53.000,49.000,49.000,50.000,47.000,47.000,53.000,50.000,59.000,66.000,73.000,78.000,77.000,73.000,72.000,79.000,83.000,82.000,83.000,82.000,81.000,81.000,82.000,83.000,76.000,78.000,75.000,77.000,78.000,94.000,94.000,94.000,90.000,90.000,93.000,93.000,90.000,90.000,87.000,85.000,86.000,92.000,90.000,88.000,91.000,92.000,98.000,100.000,96.000,92.000,82.000,79.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,76.000,75.000,75.000,76.000,97.000,14.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,76.000,76.000,75.000,76.000,76.000,76.000,77.000,77.000,77.000,76.000,76.000,77.000,76.000,76.000,76.000,71.000,71.000,69.000,70.000,66.000,64.000,58.000,59.000,58.000,62.000,60.000,75.000,71.000,69.000,68.000,65.000}
-63.727 LMS_LASER_2D_RIGHT LMS2 ID=4057,time=1225719875.374543,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=146,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.366,13.220,11.413,10.115,9.153,8.323,7.579,6.930,6.409,5.928,5.568,5.238,4.908,4.605,4.367,4.162,3.949,3.616,3.517,3.332,3.158,3.065,2.959,2.760,2.712,2.626,2.523,2.424,2.344,2.275,2.218,2.157,2.078,2.019,1.972,1.927,1.855,1.813,1.762,1.707,1.664,1.629,1.603,1.567,1.535,1.513,1.478,1.457,1.430,1.418,1.394,1.358,1.333,1.305,1.285,1.261,1.243,1.230,1.215,1.196,1.186,1.176,1.181,1.189,1.199,1.211,1.212,1.214,1.209,1.201,1.190,1.151,1.145,1.115,1.100,1.103,1.097,1.092,1.083,1.041,1.045,1.036,1.044,1.039,1.019,0.998,0.985,0.981},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,99.000,120.000,87.000,69.000,59.000,55.000,54.000,60.000,66.000,67.000,67.000,69.000,70.000,72.000,73.000,74.000,75.000,78.000,78.000,78.000,76.000,78.000,81.000,77.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,78.000,77.000,77.000,77.000,78.000,75.000,76.000,77.000,77.000,76.000,71.000,65.000,70.000,70.000,73.000,72.000,75.000,72.000,72.000,75.000,75.000,75.000,74.000,73.000,68.000,60.000,53.000,43.000,43.000,41.000,50.000,50.000,49.000,62.000,64.000,69.000,73.000,65.000,60.000,54.000,47.000,34.000,37.000,39.000,40.000,31.000,28.000,25.000,26.000,27.000}
-63.738 LMS_LASER_2D_LEFT LMS1 ID=4185,time=1225719875.382350,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=182,Range=[181]{1.019,1.021,1.033,1.044,1.049,1.049,1.063,1.069,1.083,1.089,1.094,1.104,1.113,1.127,1.132,1.149,1.157,1.178,1.183,1.196,1.208,1.233,1.243,1.264,1.277,1.280,1.310,1.319,1.338,1.357,1.374,1.396,1.409,1.424,1.457,1.481,1.512,1.521,1.556,1.583,1.606,1.625,1.661,1.689,1.717,1.752,1.786,1.826,1.861,1.894,1.929,1.976,2.005,2.044,2.104,2.159,2.217,2.259,2.309,2.377,2.455,2.527,2.602,2.625,2.619,2.638,2.751,2.829,2.898,2.956,3.014,3.092,3.200,3.312,3.417,3.551,3.683,3.754,3.929,3.925,3.922,3.944,3.981,3.997,3.998,3.987,3.993,4.000,3.974,3.996,4.039,4.089,4.107,4.099,4.120,4.136,4.132,4.132,4.141,4.143,4.130,3.536,3.483,3.456,3.415,3.393,3.373,3.365,3.359,3.387,3.407,3.456,3.842,4.199,4.217,3.558,3.433,3.402,3.345,3.290,3.262,3.246,3.239,3.233,3.220,3.212,3.209,3.201,3.199,3.190,3.186,3.185,3.186,3.188,3.303,4.474,4.494,4.502,4.527,4.548,4.565,4.583,4.609,4.635,4.658,4.676,4.692,4.711,4.739,4.763,4.778,4.802,4.836,4.861,4.880,4.913,4.936,4.960,4.994,5.020,5.055,5.081,5.116,5.142,5.185,5.223,5.248,5.285,5.321,5.355,5.410,5.423,5.468,5.490,5.445,5.481,5.915,6.329,6.387,6.443,6.507},Reflectance=[181]{40.000,41.000,43.000,44.000,42.000,42.000,41.000,44.000,42.000,45.000,44.000,44.000,46.000,48.000,46.000,45.000,45.000,44.000,42.000,44.000,46.000,41.000,42.000,44.000,45.000,48.000,53.000,49.000,50.000,46.000,50.000,52.000,54.000,53.000,49.000,52.000,54.000,54.000,54.000,54.000,53.000,54.000,54.000,54.000,54.000,51.000,41.000,39.000,39.000,36.000,33.000,37.000,30.000,30.000,33.000,45.000,39.000,45.000,46.000,49.000,52.000,49.000,50.000,52.000,54.000,58.000,52.000,52.000,49.000,48.000,47.000,47.000,47.000,54.000,54.000,48.000,58.000,70.000,75.000,77.000,76.000,72.000,73.000,76.000,76.000,75.000,75.000,74.000,71.000,71.000,73.000,74.000,77.000,77.000,75.000,77.000,79.000,79.000,79.000,79.000,78.000,96.000,97.000,96.000,92.000,91.000,89.000,93.000,95.000,92.000,92.000,96.000,90.000,78.000,78.000,99.000,99.000,95.000,92.000,81.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,76.000,77.000,100.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,76.000,76.000,76.000,76.000,76.000,78.000,77.000,77.000,77.000,76.000,76.000,77.000,77.000,74.000,72.000,69.000,69.000,69.000,66.000,63.000,59.000,59.000,58.000,62.000,62.000,79.000,71.000,69.000,68.000,66.000}
-63.738 LMS_LASER_2D_RIGHT LMS2 ID=4058,time=1225719875.387878,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=147,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.631,-1.000,15.424,12.714,10.983,9.776,8.873,8.079,7.351,6.794,6.271,5.804,5.441,5.137,4.817,4.526,4.283,4.069,3.852,3.623,3.458,3.283,3.149,3.027,2.886,2.801,2.697,2.587,2.485,2.388,2.300,2.246,2.192,2.113,2.054,2.003,1.954,1.899,1.848,1.801,1.747,1.684,1.641,1.620,1.587,1.566,1.526,1.487,1.461,1.441,1.421,1.404,1.369,1.351,1.324,1.305,1.287,1.251,1.234,1.218,1.203,1.193,1.184,1.175,1.181,1.189,1.200,1.211,1.209,1.203,1.203,1.202,1.171,1.162,1.143,1.112,1.119,1.101,1.094,1.101,1.084,1.047,1.030,1.026,1.031,1.040,1.008,0.993,0.990,0.973},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,0.000,121.000,107.000,81.000,66.000,58.000,53.000,54.000,63.000,66.000,67.000,69.000,69.000,70.000,72.000,73.000,75.000,74.000,75.000,77.000,79.000,79.000,80.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,76.000,78.000,75.000,78.000,78.000,77.000,76.000,75.000,77.000,74.000,70.000,71.000,72.000,73.000,73.000,72.000,69.000,70.000,70.000,72.000,74.000,76.000,76.000,72.000,68.000,60.000,46.000,38.000,37.000,36.000,36.000,47.000,59.000,63.000,58.000,66.000,63.000,62.000,55.000,47.000,43.000,36.000,38.000,39.000,38.000,34.000,29.000,25.000,25.000,26.000}
-63.739 DESIRED_THRUST iJoystick 87.6338999603
-63.739 DESIRED_RUDDER iJoystick 0
-62.994 CAMERA_FILE_WRITE iCameraLadybug time=1225719874.642,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.642-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.642-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.642-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.642-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.642-4.jpg
-63.750 LMS_LASER_2D_LEFT LMS1 ID=4186,time=1225719875.395689,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=183,Range=[181]{1.026,1.029,1.033,1.047,1.047,1.056,1.064,1.071,1.080,1.089,1.106,1.107,1.123,1.132,1.138,1.160,1.157,1.182,1.191,1.203,1.219,1.234,1.251,1.260,1.269,1.296,1.308,1.322,1.347,1.361,1.385,1.401,1.408,1.421,1.465,1.494,1.518,1.538,1.567,1.592,1.617,1.644,1.670,1.706,1.723,1.757,1.805,1.827,1.866,1.901,1.931,1.982,2.030,2.072,2.130,2.179,2.226,2.284,2.339,2.383,2.473,2.548,2.611,2.622,2.613,2.657,2.785,2.856,2.919,2.982,3.045,3.131,3.226,3.340,3.474,3.587,3.715,3.835,3.936,3.929,3.939,3.967,3.992,4.008,4.013,4.010,4.016,4.034,4.006,4.020,4.072,4.101,4.113,4.104,4.133,4.147,4.140,4.152,4.152,4.158,4.157,4.154,4.154,4.156,4.158,4.157,3.645,3.539,4.164,4.172,4.191,4.199,4.208,4.217,4.227,4.226,4.234,3.478,3.380,3.329,3.265,3.247,3.239,3.231,3.226,3.212,3.204,3.204,3.192,3.192,3.189,3.185,3.187,3.196,3.336,4.483,4.504,4.519,4.539,4.557,4.574,4.593,4.619,4.641,4.668,4.695,4.704,4.724,4.747,4.771,4.789,4.817,4.847,4.870,4.901,4.927,4.944,4.976,5.001,5.036,5.065,5.090,5.125,5.159,5.196,5.234,5.270,5.307,5.335,5.373,5.428,5.423,5.486,5.474,5.451,5.550,6.273,6.329,6.388,6.450,6.504},Reflectance=[181]{40.000,41.000,43.000,46.000,45.000,42.000,45.000,46.000,46.000,46.000,45.000,46.000,45.000,42.000,46.000,43.000,46.000,45.000,46.000,43.000,48.000,47.000,45.000,47.000,51.000,47.000,49.000,51.000,54.000,48.000,51.000,54.000,57.000,56.000,52.000,53.000,52.000,54.000,55.000,54.000,54.000,54.000,54.000,50.000,54.000,49.000,42.000,44.000,42.000,46.000,32.000,32.000,32.000,33.000,37.000,38.000,40.000,45.000,55.000,51.000,49.000,46.000,54.000,51.000,55.000,58.000,48.000,49.000,50.000,49.000,49.000,44.000,47.000,51.000,47.000,52.000,63.000,73.000,77.000,78.000,76.000,74.000,74.000,76.000,75.000,75.000,74.000,74.000,71.000,70.000,74.000,75.000,78.000,76.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,80.000,78.000,78.000,95.000,98.000,80.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,101.000,99.000,86.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,77.000,76.000,76.000,76.000,106.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,76.000,77.000,76.000,77.000,78.000,78.000,77.000,76.000,76.000,77.000,77.000,77.000,77.000,72.000,73.000,70.000,71.000,68.000,65.000,62.000,59.000,60.000,58.000,59.000,65.000,72.000,71.000,70.000,70.000,68.000}
-63.750 LMS_LASER_2D_RIGHT LMS2 ID=4059,time=1225719875.401211,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=148,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.492,17.515,14.498,12.075,10.559,9.461,8.609,7.871,7.192,6.606,6.118,5.690,5.337,5.032,4.740,4.448,4.197,3.978,3.780,3.581,3.417,3.252,3.103,2.982,2.858,2.749,2.652,2.543,2.443,2.356,2.267,2.235,2.165,2.096,2.044,1.969,1.927,1.875,1.829,1.785,1.714,1.671,1.641,1.615,1.586,1.542,1.507,1.477,1.467,1.430,1.409,1.377,1.357,1.338,1.315,1.289,1.269,1.250,1.224,1.208,1.201,1.186,1.179,1.175,1.185,1.188,1.190,1.199,1.207,1.198,1.200,1.170,1.163,1.146,1.123,1.128,1.116,1.104,1.094,1.089,1.077,1.039,1.026,1.031,1.024,1.023,1.004,0.998,0.984,0.976},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,27.000,60.000,117.000,102.000,75.000,63.000,57.000,52.000,56.000,64.000,66.000,68.000,69.000,69.000,71.000,73.000,75.000,76.000,75.000,75.000,78.000,78.000,79.000,80.000,78.000,80.000,80.000,81.000,81.000,81.000,78.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,76.000,78.000,79.000,78.000,75.000,70.000,74.000,77.000,72.000,65.000,70.000,75.000,75.000,74.000,73.000,71.000,68.000,68.000,71.000,76.000,77.000,75.000,71.000,62.000,52.000,52.000,49.000,37.000,35.000,49.000,63.000,65.000,64.000,70.000,63.000,61.000,59.000,55.000,49.000,41.000,36.000,39.000,38.000,34.000,30.000,28.000,24.000,25.000,25.000}
-63.763 DESIRED_THRUST iJoystick 87.6338999603
-63.763 DESIRED_RUDDER iJoystick 0
-63.763 IPLATFORM_STATUS iPlatform MainBattery=82.25,UIBattery=6.56,GainSchedule=2,OperationMode=2
-63.763 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.8596,19.9476,-0.9472},Vel=[3x1]{-0.8796,-0.6327,-9.4872},Raw=[2x1]{22.1574,-0.9472},time=1225719875.41053128242493,Speed=1.08349639321281,Pitch=0.04935378214445,Roll=0.02019018360455,PitchDot=-0.01570347613687,RollDot=0.00213118604715
-63.763 ODOMETRY_POSE iPlatform Pose=[3x1]{5.8596,19.9476,-0.9470},Vel=[3x1]{-0.8796,-0.6327,3.0792},Raw=[2x1]{22.1574,-0.9472},time=1225719875.4105,Speed=1.0835,Pitch=0.0124,Roll=0.0519,PitchDot=0.0158,RollDot=-0.0011
-63.787 DESIRED_THRUST iJoystick 87.6338999603
-63.787 DESIRED_RUDDER iJoystick 0
-63.763 LMS_LASER_2D_LEFT LMS1 ID=4187,time=1225719875.409027,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=184,Range=[181]{1.029,1.034,1.041,1.048,1.055,1.071,1.069,1.072,1.090,1.090,1.106,1.110,1.122,1.129,1.151,1.166,1.163,1.183,1.199,1.215,1.227,1.242,1.256,1.269,1.283,1.297,1.321,1.335,1.344,1.371,1.390,1.405,1.421,1.426,1.478,1.487,1.521,1.547,1.570,1.599,1.627,1.653,1.681,1.714,1.727,1.769,1.807,1.837,1.886,1.916,1.964,1.993,2.035,2.087,2.149,2.189,2.246,2.303,2.348,2.418,2.496,2.577,2.615,2.622,2.623,2.699,2.800,2.866,2.945,3.002,3.065,3.155,3.278,3.387,3.524,3.637,3.767,3.905,3.936,3.936,3.942,3.985,4.006,4.015,4.013,4.013,4.024,4.028,4.011,4.039,4.085,4.113,4.113,4.115,4.137,4.148,4.150,4.148,4.150,4.158,4.159,4.154,4.159,4.159,4.167,4.175,4.190,4.180,4.181,4.197,4.199,4.200,4.220,4.218,4.226,4.237,4.243,4.246,3.420,3.350,3.277,3.257,3.244,3.233,3.222,3.217,3.204,3.204,3.192,3.191,3.180,3.179,3.187,3.225,3.365,4.493,4.508,4.529,4.539,4.558,4.585,4.603,4.626,4.660,4.671,4.705,4.721,4.731,4.763,4.783,4.797,4.840,4.855,4.885,4.910,4.936,4.956,4.984,5.021,5.049,5.074,5.109,5.135,5.175,5.225,5.258,5.280,5.318,5.349,5.392,5.428,5.440,5.482,5.463,5.458,5.732,6.285,6.339,6.390,6.449,6.511},Reflectance=[181]{41.000,43.000,43.000,42.000,41.000,40.000,44.000,46.000,45.000,45.000,46.000,48.000,46.000,44.000,43.000,42.000,44.000,42.000,45.000,46.000,47.000,45.000,44.000,47.000,49.000,47.000,45.000,49.000,49.000,52.000,53.000,52.000,55.000,54.000,54.000,54.000,54.000,54.000,56.000,54.000,55.000,54.000,54.000,49.000,56.000,45.000,48.000,49.000,42.000,35.000,47.000,44.000,31.000,32.000,35.000,38.000,40.000,43.000,52.000,48.000,51.000,55.000,56.000,51.000,55.000,56.000,47.000,53.000,51.000,50.000,54.000,51.000,51.000,49.000,44.000,51.000,63.000,74.000,77.000,77.000,74.000,75.000,76.000,76.000,75.000,75.000,73.000,72.000,70.000,70.000,75.000,76.000,78.000,77.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,80.000,79.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,103.000,95.000,80.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,76.000,81.000,109.000,78.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,79.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,73.000,72.000,71.000,71.000,67.000,65.000,62.000,59.000,58.000,61.000,59.000,72.000,73.000,71.000,70.000,70.000,67.000}
-63.763 LMS_LASER_2D_RIGHT LMS2 ID=4060,time=1225719875.414544,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=149,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.006,26.563,16.547,13.331,11.478,10.220,9.217,8.361,7.562,6.977,6.417,5.963,5.578,5.192,4.907,4.655,4.332,4.118,3.905,3.712,3.505,3.355,3.195,3.041,2.899,2.808,2.716,2.616,2.525,2.425,2.344,2.270,2.202,2.123,2.073,1.993,1.936,1.911,1.855,1.822,1.770,1.707,1.659,1.634,1.606,1.565,1.541,1.498,1.467,1.453,1.407,1.380,1.373,1.357,1.316,1.302,1.287,1.267,1.234,1.225,1.209,1.184,1.176,1.174,1.180,1.184,1.187,1.181,1.194,1.198,1.197,1.175,1.162,1.146,1.123,1.129,1.131,1.124,1.114,1.093,1.095,1.070,1.036,1.023,1.021,1.023,1.020,0.995,0.985,0.986,0.973},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,9.000,4.000,92.000,125.000,89.000,69.000,61.000,57.000,55.000,61.000,65.000,66.000,68.000,70.000,69.000,71.000,74.000,74.000,75.000,76.000,78.000,79.000,79.000,77.000,75.000,74.000,81.000,81.000,81.000,81.000,80.000,79.000,81.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,75.000,77.000,79.000,77.000,67.000,68.000,77.000,78.000,74.000,74.000,75.000,76.000,74.000,75.000,70.000,66.000,70.000,70.000,71.000,74.000,73.000,69.000,67.000,61.000,55.000,56.000,47.000,37.000,45.000,61.000,63.000,65.000,70.000,64.000,56.000,53.000,53.000,54.000,42.000,35.000,35.000,38.000,38.000,34.000,31.000,27.000,25.000,24.000,24.000}
-63.775 LMS_LASER_2D_LEFT LMS1 ID=4188,time=1225719875.422363,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=185,Range=[181]{1.033,1.038,1.040,1.050,1.058,1.071,1.069,1.080,1.088,1.098,1.107,1.118,1.127,1.145,1.153,1.170,1.183,1.191,1.202,1.211,1.233,1.249,1.261,1.276,1.295,1.306,1.325,1.345,1.364,1.379,1.388,1.411,1.439,1.457,1.478,1.506,1.531,1.556,1.579,1.603,1.630,1.666,1.696,1.719,1.746,1.796,1.821,1.845,1.881,1.924,1.983,2.010,2.075,2.108,2.168,2.222,2.267,2.327,2.380,2.460,2.526,2.597,2.621,2.620,2.646,2.762,2.826,2.881,2.954,3.026,3.080,3.211,3.324,3.447,3.574,3.722,3.828,3.937,3.936,3.938,3.951,3.996,4.008,4.014,4.013,4.017,4.034,4.026,4.021,4.056,4.102,4.119,4.109,4.133,4.149,4.149,4.155,4.157,4.158,4.158,4.158,4.171,4.164,4.167,4.180,4.180,4.190,4.189,4.194,4.196,4.202,4.208,4.224,4.227,4.237,4.243,4.252,4.260,3.542,3.380,3.313,3.257,3.239,3.230,3.222,3.217,3.207,3.203,3.192,3.180,3.177,3.180,3.187,3.249,3.379,4.504,4.513,4.539,4.551,4.576,4.593,4.610,4.635,4.662,4.687,4.706,4.721,4.738,4.766,4.791,4.814,4.842,4.867,4.896,4.919,4.945,4.970,5.001,5.030,5.059,5.093,5.119,5.154,5.190,5.239,5.269,5.304,5.330,5.365,5.410,5.428,5.476,5.492,5.459,5.489,5.931,6.274,6.339,6.396,6.460,6.521},Reflectance=[181]{39.000,45.000,42.000,43.000,43.000,41.000,49.000,45.000,49.000,46.000,46.000,48.000,48.000,44.000,44.000,40.000,42.000,45.000,48.000,48.000,45.000,46.000,47.000,45.000,45.000,48.000,48.000,49.000,49.000,52.000,52.000,51.000,48.000,52.000,54.000,55.000,54.000,54.000,56.000,56.000,56.000,52.000,53.000,55.000,52.000,42.000,45.000,49.000,44.000,30.000,39.000,31.000,34.000,32.000,34.000,42.000,46.000,50.000,50.000,47.000,49.000,56.000,55.000,54.000,62.000,57.000,50.000,56.000,55.000,56.000,57.000,49.000,52.000,47.000,46.000,49.000,65.000,75.000,77.000,76.000,75.000,75.000,76.000,76.000,75.000,74.000,74.000,72.000,70.000,72.000,75.000,78.000,77.000,77.000,78.000,79.000,80.000,78.000,79.000,79.000,80.000,81.000,80.000,79.000,79.000,79.000,80.000,80.000,81.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,78.000,78.000,101.000,100.000,86.000,79.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,77.000,76.000,77.000,76.000,86.000,107.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,76.000,77.000,77.000,78.000,77.000,78.000,73.000,74.000,72.000,72.000,69.000,66.000,63.000,62.000,59.000,58.000,59.000,61.000,80.000,73.000,71.000,72.000,71.000,68.000}
-63.786 LMS_LASER_2D_LEFT LMS1 ID=4189,time=1225719875.435698,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=186,Range=[181]{1.035,1.039,1.042,1.056,1.062,1.075,1.074,1.077,1.086,1.098,1.122,1.126,1.133,1.149,1.158,1.168,1.184,1.189,1.209,1.219,1.234,1.251,1.263,1.282,1.299,1.316,1.335,1.351,1.363,1.380,1.400,1.418,1.453,1.472,1.484,1.514,1.551,1.574,1.583,1.616,1.642,1.671,1.702,1.723,1.754,1.807,1.829,1.874,1.911,1.947,1.977,2.020,2.078,2.134,2.186,2.235,2.280,2.328,2.374,2.474,2.550,2.606,2.626,2.617,2.654,2.783,2.831,2.875,2.958,3.052,3.116,3.226,3.370,3.474,3.615,3.763,3.852,3.942,3.938,3.939,3.968,4.000,4.013,4.015,4.018,4.022,4.037,4.018,4.032,4.079,4.110,4.122,4.113,4.143,4.150,4.149,4.152,4.158,4.158,4.167,4.171,4.168,4.168,4.168,4.178,4.194,4.193,4.182,4.200,4.197,4.213,4.218,4.227,4.229,4.237,4.248,4.253,4.276,4.281,3.428,3.352,3.276,3.246,3.230,3.221,3.217,3.209,3.198,3.184,3.184,3.173,3.181,3.179,3.222,3.360,4.506,4.529,4.554,4.558,4.579,4.594,4.609,4.642,4.672,4.691,4.713,4.729,4.755,4.776,4.800,4.835,4.852,4.877,4.904,4.933,4.959,4.976,5.013,5.039,5.065,5.101,5.135,5.169,5.212,5.256,5.279,5.318,5.344,5.382,5.419,5.432,5.483,5.483,5.457,5.550,6.191,6.247,6.308,6.373,6.432,6.506},Reflectance=[181]{44.000,45.000,43.000,46.000,46.000,43.000,47.000,48.000,49.000,45.000,40.000,43.000,47.000,45.000,42.000,43.000,42.000,46.000,47.000,48.000,47.000,46.000,48.000,49.000,48.000,48.000,49.000,48.000,49.000,52.000,50.000,47.000,42.000,48.000,53.000,55.000,52.000,54.000,54.000,54.000,57.000,54.000,48.000,57.000,48.000,43.000,46.000,38.000,36.000,34.000,32.000,30.000,33.000,33.000,35.000,40.000,44.000,55.000,55.000,49.000,51.000,56.000,52.000,56.000,61.000,54.000,56.000,63.000,52.000,52.000,58.000,51.000,53.000,51.000,44.000,59.000,71.000,77.000,78.000,76.000,75.000,77.000,75.000,76.000,74.000,73.000,72.000,69.000,71.000,74.000,75.000,78.000,76.000,77.000,79.000,79.000,79.000,78.000,78.000,80.000,81.000,80.000,79.000,79.000,79.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,103.000,97.000,80.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,80.000,105.000,79.000,78.000,80.000,79.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,71.000,74.000,73.000,71.000,68.000,69.000,63.000,59.000,58.000,58.000,58.000,62.000,75.000,73.000,72.000,73.000,70.000,68.000}
-63.786 LMS_LASER_2D_RIGHT LMS2 ID=4061,time=1225719875.427887,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=150,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.313,-1.000,15.865,12.874,11.006,9.874,8.931,8.158,7.402,6.851,6.288,5.822,5.494,5.119,4.800,4.527,4.301,4.027,3.840,3.625,3.449,3.287,3.146,2.987,2.890,2.807,2.689,2.589,2.478,2.382,2.328,2.246,2.167,2.108,2.064,1.978,1.937,1.885,1.841,1.806,1.759,1.671,1.642,1.606,1.583,1.553,1.518,1.487,1.465,1.446,1.423,1.398,1.374,1.333,1.317,1.296,1.285,1.251,1.234,1.209,1.186,1.177,1.168,1.167,1.180,1.179,1.185,1.187,1.197,1.201,1.200,1.185,1.171,1.149,1.130,1.129,1.134,1.120,1.107,1.098,1.085,1.061,1.024,1.023,1.021,1.029,1.027,1.023,0.976,0.981,0.968},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,20.000,0.000,109.000,116.000,83.000,66.000,60.000,54.000,54.000,61.000,65.000,67.000,68.000,69.000,69.000,73.000,73.000,74.000,76.000,76.000,77.000,77.000,78.000,79.000,78.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,81.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,79.000,77.000,70.000,72.000,77.000,76.000,74.000,77.000,78.000,78.000,77.000,74.000,75.000,74.000,74.000,72.000,67.000,70.000,69.000,71.000,74.000,77.000,76.000,71.000,66.000,59.000,54.000,51.000,45.000,40.000,40.000,51.000,60.000,61.000,66.000,60.000,57.000,55.000,53.000,49.000,39.000,37.000,34.000,38.000,40.000,37.000,35.000,34.000,25.000,25.000,25.000}
-63.794 LMS2_STATUS LMS2 AppErrorFlag=false,Uptime=-1619.73,MOOSName=LMS2,Publishing=LMS2_STATUS,LMS_LASER_2D_RIGHT,MOOS_DEBUG,Subscribing=LASER_LAG,LMS2_CMD,LOCAL_LASER_LAG,
-63.799 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.8942,19.9726,-0.9434},Vel=[3x1]{-0.8511,-0.6172,-3.5897},Raw=[2x1]{22.2001,-0.9434},time=1225719875.44652509689331,Speed=1.05137116322537,Pitch=0.04935378214445,Roll=0.02692024480606,PitchDot=-0.00000000000000,RollDot=0.00197415128578
-63.799 ODOMETRY_POSE iPlatform Pose=[3x1]{5.8942,19.9726,-0.9429},Vel=[3x1]{-0.8511,-0.6172,2.6935},Raw=[2x1]{22.2001,-0.9434},time=1225719875.4465,Speed=1.0514,Pitch=0.0072,Roll=0.0558,PitchDot=0.0009,RollDot=-0.0018
-63.811 DESIRED_THRUST iJoystick 87.6338999603
-63.811 DESIRED_RUDDER iJoystick 0
-63.798 LMS_LASER_2D_LEFT LMS1 ID=4190,time=1225719875.449031,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=187,Range=[181]{1.038,1.046,1.051,1.056,1.063,1.077,1.080,1.092,1.106,1.107,1.116,1.132,1.139,1.141,1.166,1.180,1.183,1.199,1.214,1.221,1.237,1.252,1.265,1.288,1.303,1.318,1.342,1.353,1.380,1.389,1.411,1.433,1.463,1.482,1.495,1.530,1.553,1.584,1.592,1.629,1.653,1.671,1.709,1.734,1.779,1.809,1.838,1.889,1.916,1.960,1.993,2.039,2.108,2.155,2.202,2.249,2.308,2.347,2.406,2.502,2.574,2.616,2.629,2.627,2.694,2.818,2.853,2.887,2.978,3.081,3.165,3.294,3.392,3.507,3.666,3.794,3.896,3.945,3.942,3.961,3.987,4.005,4.017,4.023,4.018,4.025,4.037,4.019,4.039,4.089,4.115,4.116,4.124,4.149,4.150,4.149,4.154,4.157,4.164,4.164,4.165,4.159,4.173,4.181,4.182,4.192,4.194,4.193,4.198,4.204,4.215,4.218,4.235,4.237,4.246,4.252,4.261,4.270,4.278,3.525,3.374,3.304,3.257,3.229,3.222,3.214,3.210,3.198,3.189,3.177,3.168,3.175,3.180,3.218,3.351,3.279,4.535,4.549,4.568,4.590,4.603,4.628,4.652,4.680,4.699,4.723,4.739,4.769,4.784,4.806,4.842,4.861,4.889,4.916,4.939,4.972,4.993,5.025,5.053,5.078,5.111,5.144,5.183,5.236,5.264,5.301,5.322,5.362,5.391,5.437,5.445,5.481,5.472,5.468,5.723,6.174,6.238,6.293,6.354,6.417,6.495},Reflectance=[181]{41.000,41.000,43.000,46.000,45.000,44.000,45.000,47.000,45.000,46.000,47.000,45.000,46.000,47.000,42.000,40.000,42.000,45.000,49.000,49.000,48.000,47.000,49.000,47.000,45.000,53.000,48.000,49.000,49.000,52.000,51.000,49.000,43.000,48.000,54.000,54.000,52.000,55.000,54.000,52.000,54.000,54.000,55.000,55.000,42.000,44.000,46.000,40.000,34.000,37.000,34.000,29.000,36.000,36.000,41.000,42.000,40.000,55.000,54.000,50.000,54.000,56.000,50.000,57.000,58.000,47.000,59.000,59.000,54.000,50.000,47.000,46.000,59.000,53.000,47.000,65.000,73.000,78.000,77.000,75.000,75.000,75.000,77.000,76.000,74.000,71.000,72.000,70.000,70.000,74.000,77.000,79.000,77.000,78.000,79.000,79.000,79.000,78.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,79.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,103.000,103.000,86.000,78.000,78.000,79.000,80.000,80.000,79.000,79.000,79.000,78.000,78.000,77.000,80.000,105.000,16.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,77.000,79.000,78.000,79.000,79.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,73.000,73.000,74.000,74.000,70.000,68.000,66.000,62.000,57.000,63.000,63.000,59.000,72.000,73.000,73.000,73.000,72.000,71.000,70.000}
-63.798 LMS_LASER_2D_RIGHT LMS2 ID=4062,time=1225719875.441228,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=151,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.916,18.187,14.934,12.225,10.611,9.523,8.663,7.893,7.201,6.651,6.127,5.733,5.336,5.007,4.732,4.448,4.213,3.976,3.771,3.590,3.406,3.216,3.049,2.963,2.858,2.762,2.662,2.532,2.425,2.381,2.310,2.237,2.147,2.090,2.020,1.962,1.912,1.884,1.830,1.779,1.707,1.658,1.649,1.607,1.573,1.536,1.518,1.491,1.464,1.444,1.414,1.382,1.366,1.343,1.314,1.296,1.278,1.258,1.234,1.200,1.178,1.180,1.168,1.166,1.179,1.197,1.199,1.197,1.187,1.194,1.192,1.186,1.184,1.152,1.129,1.126,1.115,1.111,1.112,1.098,1.071,1.066,1.027,1.019,1.019,1.031,1.022,1.011,1.015,0.968,0.966},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,45.000,29.000,118.000,108.000,77.000,64.000,57.000,54.000,56.000,64.000,66.000,68.000,69.000,69.000,70.000,73.000,74.000,75.000,75.000,76.000,78.000,80.000,82.000,79.000,81.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,77.000,75.000,78.000,74.000,74.000,74.000,77.000,78.000,78.000,78.000,76.000,75.000,76.000,74.000,71.000,72.000,69.000,67.000,71.000,71.000,74.000,77.000,77.000,70.000,55.000,42.000,42.000,39.000,39.000,43.000,42.000,41.000,46.000,58.000,66.000,62.000,61.000,59.000,52.000,46.000,45.000,47.000,37.000,40.000,40.000,42.000,52.000,56.000,41.000,25.000,24.000}
-63.810 LMS_LASER_2D_RIGHT LMS2 ID=4063,time=1225719875.454569,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=152,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.517,17.044,14.115,11.788,10.322,9.316,8.483,7.697,7.009,6.513,6.025,5.646,5.264,4.935,4.655,4.368,4.120,3.908,3.719,3.545,3.358,3.189,3.078,2.937,2.829,2.734,2.600,2.483,2.443,2.354,2.286,2.202,2.140,2.079,2.002,1.959,1.911,1.878,1.815,1.754,1.685,1.663,1.644,1.598,1.569,1.517,1.492,1.477,1.455,1.432,1.402,1.375,1.356,1.341,1.321,1.286,1.258,1.240,1.200,1.176,1.178,1.165,1.158,1.164,1.177,1.190,1.196,1.198,1.189,1.178,1.190,1.169,1.168,1.145,1.125,1.121,1.111,1.105,1.093,1.078,1.055,1.056,1.022,1.019,1.014,1.021,1.020,1.013,1.016,0.976,0.959},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,23.000,75.000,117.000,98.000,72.000,62.000,56.000,55.000,59.000,65.000,67.000,67.000,69.000,70.000,72.000,74.000,75.000,76.000,75.000,78.000,77.000,80.000,80.000,79.000,80.000,81.000,82.000,80.000,81.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,78.000,75.000,80.000,80.000,72.000,76.000,72.000,74.000,77.000,76.000,77.000,76.000,76.000,75.000,72.000,68.000,69.000,67.000,66.000,71.000,73.000,77.000,76.000,72.000,66.000,54.000,40.000,39.000,35.000,35.000,33.000,42.000,54.000,54.000,55.000,61.000,60.000,59.000,56.000,51.000,44.000,49.000,40.000,38.000,40.000,38.000,42.000,52.000,57.000,43.000,28.000,25.000}
-63.822 LMS_LASER_2D_LEFT LMS1 ID=4191,time=1225719875.462375,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=188,Range=[181]{1.038,1.042,1.051,1.056,1.065,1.081,1.090,1.092,1.107,1.113,1.124,1.134,1.140,1.148,1.169,1.182,1.193,1.207,1.211,1.231,1.242,1.263,1.280,1.285,1.305,1.317,1.337,1.362,1.380,1.394,1.414,1.442,1.466,1.482,1.517,1.539,1.560,1.587,1.610,1.635,1.663,1.675,1.719,1.752,1.784,1.825,1.847,1.891,1.940,1.976,2.006,2.051,2.113,2.161,2.217,2.265,2.327,2.350,2.429,2.526,2.590,2.616,2.630,2.635,2.745,2.838,2.890,2.951,3.030,3.110,3.206,3.316,3.427,3.577,3.713,3.820,3.941,3.943,3.945,3.958,3.996,4.012,4.016,4.021,4.023,4.027,4.033,4.024,4.049,4.098,4.119,4.118,4.129,4.148,4.150,4.154,4.167,4.168,4.174,4.168,4.167,4.173,4.172,4.178,4.192,4.197,4.202,4.206,4.200,4.215,4.214,4.227,4.232,4.240,4.246,4.258,4.260,4.281,4.287,4.300,3.430,3.355,3.284,3.237,3.229,3.213,3.210,3.200,3.187,3.178,3.171,3.168,3.172,3.185,3.312,3.473,4.539,4.554,4.570,4.594,4.616,4.636,4.664,4.688,4.714,4.729,4.749,4.768,4.790,4.814,4.835,4.862,4.895,4.921,4.956,4.970,5.003,5.033,5.060,5.091,5.122,5.151,5.195,5.245,5.275,5.302,5.328,5.361,5.410,5.431,5.462,5.489,5.460,5.479,5.840,6.152,6.211,6.266,6.333,6.385,6.456},Reflectance=[181]{41.000,43.000,43.000,46.000,47.000,45.000,45.000,47.000,45.000,46.000,42.000,43.000,50.000,46.000,43.000,45.000,43.000,46.000,48.000,46.000,46.000,36.000,43.000,50.000,51.000,49.000,49.000,49.000,52.000,55.000,49.000,49.000,44.000,48.000,48.000,50.000,48.000,52.000,55.000,46.000,55.000,56.000,55.000,51.000,44.000,43.000,49.000,38.000,39.000,49.000,36.000,29.000,34.000,42.000,44.000,44.000,45.000,56.000,49.000,49.000,57.000,56.000,50.000,56.000,53.000,48.000,56.000,49.000,46.000,51.000,46.000,49.000,54.000,52.000,49.000,64.000,74.000,77.000,75.000,74.000,75.000,77.000,76.000,75.000,73.000,72.000,71.000,69.000,70.000,74.000,78.000,79.000,75.000,78.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,81.000,81.000,82.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,80.000,78.000,79.000,79.000,79.000,105.000,100.000,84.000,78.000,78.000,79.000,80.000,79.000,80.000,79.000,79.000,78.000,77.000,76.000,100.000,111.000,79.000,80.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,72.000,73.000,74.000,72.000,69.000,68.000,63.000,58.000,61.000,61.000,60.000,60.000,76.000,74.000,73.000,73.000,72.000,69.000,69.000}
-63.822 LMS_LASER_2D_RIGHT LMS2 ID=4064,time=1225719875.467907,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=153,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.381,13.170,11.337,10.022,9.103,8.273,7.457,6.882,6.391,5.895,5.535,5.156,4.855,4.605,4.322,4.046,3.835,3.663,3.501,3.316,3.168,3.008,2.906,2.804,2.707,2.566,2.473,2.411,2.327,2.265,2.193,2.113,2.053,1.993,1.944,1.904,1.859,1.806,1.731,1.671,1.653,1.625,1.590,1.570,1.523,1.495,1.478,1.442,1.411,1.396,1.369,1.347,1.315,1.296,1.278,1.242,1.225,1.200,1.176,1.170,1.160,1.157,1.171,1.182,1.185,1.188,1.181,1.185,1.191,1.189,1.183,1.165,1.150,1.128,1.117,1.114,1.099,1.088,1.074,1.075,1.051,1.023,1.015,1.017,1.018,1.020,1.013,0.996,0.961,0.948},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,95.000,123.000,85.000,69.000,60.000,56.000,56.000,63.000,65.000,67.000,67.000,69.000,71.000,71.000,73.000,74.000,74.000,74.000,79.000,75.000,79.000,80.000,80.000,80.000,81.000,82.000,82.000,82.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,73.000,74.000,79.000,79.000,80.000,78.000,75.000,77.000,77.000,74.000,75.000,76.000,76.000,75.000,72.000,71.000,69.000,70.000,69.000,71.000,72.000,74.000,74.000,71.000,66.000,52.000,47.000,39.000,35.000,34.000,33.000,39.000,46.000,49.000,53.000,59.000,57.000,52.000,46.000,52.000,57.000,51.000,39.000,36.000,41.000,41.000,44.000,45.000,53.000,32.000,27.000,26.000}
-63.835 DESIRED_THRUST iJoystick 87.6338999603
-63.835 DESIRED_RUDDER iJoystick 0
-63.835 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.9285,19.9976,-0.9392},Vel=[3x1]{-0.8450,-0.6182,-6.9231},Raw=[2x1]{22.2425,-0.9392},time=1225719875.48249125480652,Speed=1.04699045004527,Pitch=0.04935378214445,Roll=0.03365030600758,PitchDot=-0.01570347613687,RollDot=0.00141331285232
-63.835 ODOMETRY_POSE iPlatform Pose=[3x1]{5.9285,19.9976,-0.9384},Vel=[3x1]{-0.8450,-0.6182,-0.6400},Raw=[2x1]{22.2425,-0.9392},time=1225719875.4825,Speed=1.0470,Pitch=0.0020,Roll=0.0597,PitchDot=-0.0134,RollDot=-0.0082
-63.842 DB_TIME MOOSDB#1 1225719875.49
-63.842 DB_UPTIME MOOSDB#1 67.3463785648
-63.834 LMS_LASER_2D_LEFT LMS1 ID=4192,time=1225719875.475717,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=189,Range=[181]{1.041,1.047,1.058,1.057,1.069,1.084,1.091,1.089,1.108,1.117,1.128,1.136,1.140,1.166,1.166,1.187,1.198,1.204,1.225,1.231,1.253,1.270,1.280,1.290,1.308,1.329,1.336,1.369,1.388,1.399,1.417,1.442,1.468,1.486,1.516,1.539,1.565,1.600,1.620,1.644,1.657,1.677,1.726,1.761,1.794,1.835,1.858,1.902,1.941,1.971,2.018,2.067,2.130,2.174,2.223,2.269,2.317,2.341,2.454,2.543,2.586,2.631,2.629,2.654,2.778,2.844,2.911,2.980,3.042,3.152,3.230,3.344,3.458,3.603,3.770,3.845,3.948,3.938,3.942,3.967,3.996,4.014,4.023,4.018,4.020,4.033,4.026,4.021,4.063,4.107,4.118,4.116,4.134,4.148,4.149,4.158,4.157,4.166,4.170,4.168,4.167,4.168,4.174,4.176,4.186,4.192,4.189,4.198,4.204,4.211,4.216,4.225,4.231,4.235,4.246,4.257,4.269,4.278,4.285,4.296,4.306,3.411,3.326,3.247,3.229,3.215,3.204,3.195,3.175,3.169,3.158,3.164,3.155,3.175,3.258,3.373,3.268,4.558,4.574,4.594,4.611,4.642,4.671,4.691,4.712,4.729,4.745,4.775,4.796,4.815,4.844,4.869,4.904,4.925,4.962,4.980,5.009,5.041,5.071,5.091,5.126,5.167,5.208,5.255,5.282,5.316,5.343,5.373,5.428,5.443,5.472,5.481,5.458,5.515,5.956,6.137,6.197,6.257,6.312,6.377,6.430},Reflectance=[181]{43.000,45.000,43.000,47.000,44.000,43.000,42.000,46.000,42.000,42.000,36.000,44.000,46.000,45.000,45.000,44.000,41.000,44.000,45.000,46.000,43.000,38.000,48.000,48.000,49.000,46.000,49.000,48.000,48.000,50.000,46.000,49.000,49.000,50.000,48.000,50.000,46.000,51.000,52.000,46.000,56.000,61.000,51.000,42.000,46.000,48.000,50.000,41.000,39.000,54.000,33.000,31.000,40.000,40.000,47.000,43.000,57.000,61.000,48.000,52.000,55.000,51.000,53.000,57.000,52.000,47.000,47.000,48.000,48.000,49.000,49.000,50.000,52.000,51.000,44.000,63.000,76.000,76.000,74.000,74.000,75.000,76.000,76.000,74.000,72.000,71.000,69.000,68.000,72.000,74.000,77.000,77.000,74.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,79.000,79.000,103.000,91.000,78.000,78.000,79.000,79.000,79.000,80.000,79.000,78.000,77.000,77.000,75.000,86.000,108.000,20.000,79.000,78.000,78.000,79.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,75.000,76.000,77.000,76.000,77.000,77.000,76.000,68.000,74.000,74.000,71.000,68.000,65.000,61.000,60.000,63.000,64.000,59.000,57.000,76.000,72.000,72.000,73.000,68.000,69.000,69.000}
-63.834 LMS_LASER_2D_RIGHT LMS2 ID=4065,time=1225719875.481245,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=154,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.249,-1.000,15.781,12.906,10.759,9.811,8.996,8.146,7.313,6.802,6.280,5.821,5.441,5.111,4.783,4.544,4.273,4.036,3.749,3.628,3.480,3.273,3.147,2.989,2.880,2.771,2.667,2.569,2.471,2.400,2.310,2.265,2.184,2.103,2.046,2.002,1.933,1.886,1.839,1.804,1.716,1.661,1.634,1.605,1.589,1.562,1.533,1.499,1.458,1.422,1.396,1.378,1.361,1.330,1.308,1.276,1.262,1.248,1.227,1.201,1.176,1.169,1.168,1.165,1.175,1.176,1.173,1.182,1.186,1.182,1.187,1.175,1.167,1.149,1.136,1.130,1.117,1.109,1.101,1.091,1.074,1.068,1.050,1.014,1.011,1.015,1.014,1.006,0.991,0.971,0.956,0.953},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,17.000,0.000,112.000,114.000,93.000,64.000,57.000,57.000,57.000,63.000,66.000,67.000,68.000,68.000,71.000,72.000,72.000,74.000,74.000,77.000,78.000,78.000,81.000,80.000,80.000,81.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,81.000,80.000,80.000,72.000,72.000,77.000,78.000,79.000,79.000,78.000,78.000,74.000,71.000,74.000,77.000,77.000,76.000,74.000,75.000,77.000,75.000,73.000,73.000,74.000,77.000,77.000,69.000,61.000,58.000,52.000,37.000,36.000,33.000,34.000,31.000,36.000,50.000,55.000,56.000,54.000,54.000,50.000,47.000,50.000,44.000,54.000,36.000,39.000,41.000,40.000,34.000,30.000,29.000,26.000,25.000}
-63.846 LMS_LASER_2D_LEFT LMS1 ID=4193,time=1225719875.489058,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=190,Range=[181]{1.046,1.049,1.060,1.059,1.082,1.081,1.090,1.098,1.104,1.124,1.126,1.138,1.143,1.160,1.174,1.182,1.203,1.217,1.230,1.240,1.258,1.267,1.288,1.294,1.316,1.331,1.352,1.371,1.389,1.410,1.424,1.442,1.476,1.490,1.523,1.556,1.578,1.601,1.624,1.651,1.671,1.683,1.737,1.774,1.802,1.843,1.875,1.912,1.948,1.959,2.038,2.088,2.128,2.184,2.232,2.284,2.325,2.351,2.459,2.559,2.614,2.635,2.631,2.667,2.790,2.857,2.929,2.995,3.063,3.163,3.239,3.358,3.473,3.645,3.805,3.854,3.939,3.941,3.943,3.967,4.004,4.016,4.022,4.016,4.022,4.037,4.018,4.031,4.073,4.108,4.118,4.115,4.152,4.147,4.152,4.158,4.156,4.173,4.165,4.168,4.170,4.178,4.176,4.183,4.184,4.198,4.198,4.192,4.198,4.208,4.217,4.226,4.226,4.239,4.252,4.260,4.270,4.279,4.292,4.295,4.314,3.602,3.375,3.316,3.240,3.211,3.209,3.200,3.180,3.171,3.162,3.157,3.153,3.157,3.184,3.310,3.420,3.341,4.584,4.602,4.619,4.642,4.676,4.690,4.706,4.734,4.749,4.776,4.793,4.825,4.852,4.878,4.901,4.936,4.959,4.982,5.019,5.044,5.070,5.099,5.137,5.164,5.214,5.260,5.284,5.323,5.340,5.399,5.436,5.442,5.472,5.481,5.457,5.565,6.088,6.151,6.201,6.252,6.305,6.363,6.418},Reflectance=[181]{45.000,42.000,44.000,43.000,42.000,45.000,45.000,45.000,44.000,45.000,43.000,46.000,48.000,48.000,45.000,45.000,43.000,42.000,40.000,46.000,45.000,46.000,42.000,46.000,43.000,47.000,48.000,49.000,49.000,51.000,50.000,49.000,46.000,52.000,51.000,46.000,43.000,47.000,50.000,53.000,54.000,55.000,48.000,40.000,46.000,43.000,42.000,42.000,43.000,56.000,41.000,37.000,43.000,41.000,47.000,45.000,61.000,62.000,50.000,51.000,55.000,49.000,54.000,58.000,54.000,49.000,47.000,51.000,49.000,50.000,53.000,52.000,55.000,46.000,54.000,71.000,76.000,77.000,72.000,74.000,75.000,76.000,75.000,74.000,71.000,70.000,67.000,68.000,72.000,75.000,77.000,77.000,77.000,78.000,79.000,79.000,78.000,80.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,80.000,80.000,79.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,97.000,94.000,91.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,75.000,75.000,98.000,110.000,4.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,78.000,77.000,78.000,77.000,76.000,76.000,76.000,76.000,77.000,78.000,73.000,67.000,72.000,72.000,70.000,67.000,60.000,61.000,59.000,64.000,63.000,58.000,59.000,74.000,74.000,73.000,72.000,69.000,68.000,68.000}
-63.846 LMS_LASER_2D_RIGHT LMS2 ID=4066,time=1225719875.494581,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=155,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.929,-1.000,15.478,12.692,10.689,9.676,8.876,8.025,7.208,6.696,6.225,5.759,5.398,5.084,4.757,4.466,4.230,3.762,3.701,3.607,3.447,3.237,3.125,2.979,2.872,2.740,2.649,2.550,2.469,2.400,2.321,2.255,2.180,2.097,2.046,1.982,1.931,1.872,1.819,1.779,1.698,1.659,1.642,1.610,1.581,1.551,1.532,1.489,1.466,1.421,1.379,1.366,1.348,1.318,1.300,1.276,1.262,1.235,1.209,1.193,1.184,1.174,1.168,1.165,1.169,1.164,1.168,1.180,1.177,1.184,1.185,1.180,1.178,1.157,1.132,1.124,1.110,1.100,1.095,1.089,1.071,1.056,1.052,1.014,1.003,1.009,1.004,1.019,0.999,1.005,0.995,0.947},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,43.000,0.000,116.000,111.000,89.000,64.000,55.000,57.000,56.000,63.000,66.000,67.000,68.000,68.000,70.000,73.000,73.000,83.000,75.000,76.000,76.000,78.000,80.000,79.000,80.000,77.000,79.000,80.000,80.000,81.000,81.000,80.000,79.000,81.000,81.000,79.000,79.000,79.000,78.000,80.000,74.000,68.000,71.000,75.000,79.000,78.000,78.000,78.000,74.000,70.000,72.000,75.000,76.000,75.000,75.000,75.000,74.000,72.000,72.000,73.000,76.000,75.000,73.000,68.000,62.000,56.000,54.000,45.000,36.000,36.000,41.000,37.000,43.000,49.000,53.000,53.000,54.000,54.000,52.000,52.000,52.000,53.000,48.000,36.000,37.000,39.000,37.000,37.000,31.000,40.000,40.000,27.000}
-63.859 LMS_LASER_2D_RIGHT LMS2 ID=4067,time=1225719875.507916,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=156,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.025,18.397,15.167,12.474,10.562,9.584,8.794,7.961,7.206,6.651,6.181,5.715,5.336,5.032,4.740,4.438,4.194,3.704,3.689,3.589,3.393,3.233,3.098,2.979,2.863,2.729,2.644,2.543,2.461,2.373,2.302,2.237,2.153,2.088,2.044,1.985,1.932,1.860,1.806,1.776,1.721,1.665,1.657,1.612,1.578,1.544,1.518,1.490,1.461,1.403,1.378,1.360,1.346,1.329,1.306,1.287,1.265,1.239,1.220,1.207,1.184,1.176,1.166,1.170,1.166,1.161,1.170,1.176,1.183,1.172,1.177,1.160,1.150,1.134,1.131,1.119,1.106,1.092,1.085,1.085,1.072,1.069,1.050,1.009,0.998,0.999,1.010,1.003,0.972,0.968,0.958,0.945},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,26.000,37.000,119.000,108.000,86.000,63.000,55.000,57.000,55.000,64.000,66.000,67.000,69.000,68.000,70.000,72.000,72.000,81.000,74.000,75.000,75.000,80.000,80.000,79.000,80.000,77.000,81.000,81.000,81.000,81.000,81.000,80.000,72.000,81.000,80.000,80.000,79.000,78.000,75.000,79.000,75.000,75.000,78.000,78.000,78.000,79.000,79.000,78.000,77.000,71.000,72.000,73.000,75.000,75.000,73.000,71.000,63.000,64.000,62.000,68.000,76.000,73.000,69.000,64.000,61.000,58.000,51.000,50.000,38.000,35.000,47.000,54.000,57.000,62.000,56.000,51.000,52.000,54.000,55.000,55.000,53.000,48.000,43.000,35.000,36.000,36.000,37.000,37.000,26.000,25.000,26.000,27.000}
-63.859 DESIRED_THRUST iJoystick 87.6338999603
-63.859 DESIRED_RUDDER iJoystick 0
-63.871 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.9541,20.0163,-0.9367},Vel=[3x1]{-0.8387,-0.6168,0.7692},Raw=[2x1]{22.2742,-0.9367},time=1225719875.51847529411316,Speed=1.04114949913846,Pitch=0.04711042841061,Roll=0.03589365974142,PitchDot=-0.02243353733839,RollDot=0.00069543965749
-63.871 ODOMETRY_POSE iPlatform Pose=[3x1]{5.9541,20.0163,-0.9358},Vel=[3x1]{-0.8387,-0.6168,0.7693},Raw=[2x1]{22.2742,-0.9367},time=1225719875.5185,Speed=1.0411,Pitch=-0.0010,Roll=0.0592,PitchDot=-0.0156,RollDot=0.0161
-63.858 LMS_LASER_2D_LEFT LMS1 ID=4194,time=1225719875.502398,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=191,Range=[181]{1.042,1.047,1.060,1.068,1.073,1.077,1.090,1.098,1.111,1.115,1.139,1.142,1.153,1.162,1.170,1.191,1.199,1.216,1.223,1.230,1.253,1.271,1.276,1.303,1.317,1.339,1.347,1.370,1.380,1.411,1.424,1.449,1.474,1.495,1.515,1.546,1.584,1.600,1.624,1.650,1.682,1.715,1.745,1.768,1.804,1.836,1.868,1.919,1.953,1.968,2.027,2.077,2.126,2.179,2.239,2.293,2.328,2.342,2.442,2.565,2.621,2.629,2.625,2.676,2.808,2.862,2.921,2.992,3.074,3.169,3.262,3.362,3.526,3.681,3.822,3.850,3.932,3.946,3.947,3.972,4.002,4.014,4.021,4.020,4.018,4.037,4.020,4.031,4.075,4.108,4.119,4.111,4.144,4.148,4.149,4.161,4.157,4.161,4.163,4.165,4.171,4.175,4.172,4.186,4.188,4.184,4.196,4.196,4.199,4.209,4.208,4.229,4.234,4.243,4.253,4.260,4.267,4.276,4.293,4.298,4.314,3.659,3.694,3.431,3.323,3.262,3.212,3.194,3.180,3.169,3.162,3.150,3.146,3.155,3.157,3.183,3.310,3.404,3.288,4.601,4.618,4.642,4.666,4.690,4.706,4.733,4.749,4.775,4.797,4.825,4.851,4.871,4.903,4.933,4.960,4.980,5.007,5.043,5.070,5.102,5.132,5.170,5.225,5.260,5.284,5.315,5.347,5.396,5.437,5.431,5.481,5.483,5.460,5.585,6.102,6.156,6.200,6.249,6.305,6.353,6.424},Reflectance=[181]{39.000,45.000,44.000,39.000,46.000,48.000,45.000,46.000,48.000,46.000,41.000,47.000,44.000,49.000,44.000,45.000,46.000,45.000,46.000,49.000,47.000,48.000,46.000,45.000,44.000,46.000,50.000,52.000,49.000,48.000,50.000,49.000,49.000,54.000,51.000,50.000,42.000,47.000,49.000,53.000,51.000,49.000,52.000,54.000,46.000,49.000,43.000,37.000,38.000,56.000,44.000,44.000,43.000,43.000,45.000,46.000,59.000,63.000,54.000,54.000,50.000,50.000,56.000,58.000,54.000,48.000,48.000,50.000,47.000,53.000,48.000,50.000,46.000,43.000,58.000,72.000,76.000,75.000,73.000,73.000,75.000,76.000,75.000,72.000,69.000,70.000,67.000,68.000,72.000,75.000,78.000,75.000,77.000,78.000,79.000,79.000,78.000,79.000,79.000,80.000,81.000,78.000,77.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,98.000,97.000,105.000,93.000,83.000,79.000,78.000,79.000,79.000,79.000,78.000,77.000,77.000,75.000,75.000,98.000,112.000,6.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,78.000,77.000,77.000,75.000,75.000,75.000,76.000,78.000,76.000,72.000,68.000,72.000,72.000,68.000,65.000,59.000,61.000,58.000,65.000,58.000,60.000,64.000,73.000,73.000,72.000,71.000,69.000,67.000,70.000}
-63.871 LMS_LASER_2D_LEFT LMS1 ID=4195,time=1225719875.515738,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=192,Range=[181]{1.044,1.049,1.060,1.072,1.078,1.079,1.090,1.102,1.106,1.117,1.141,1.141,1.156,1.162,1.176,1.188,1.199,1.221,1.228,1.234,1.250,1.276,1.285,1.302,1.329,1.330,1.353,1.371,1.392,1.412,1.429,1.461,1.477,1.499,1.514,1.547,1.585,1.607,1.626,1.646,1.688,1.711,1.748,1.770,1.802,1.837,1.884,1.921,1.960,1.968,2.015,2.096,2.132,2.179,2.239,2.298,2.347,2.360,2.487,2.555,2.608,2.634,2.625,2.685,2.825,2.863,2.924,2.997,3.077,3.179,3.239,3.353,3.530,3.695,3.817,3.856,3.921,3.941,3.941,3.968,4.004,4.013,4.018,4.017,4.018,4.038,4.008,4.029,4.081,4.111,4.122,4.113,4.153,4.148,4.149,4.158,4.159,4.161,4.167,4.168,4.172,4.168,4.174,4.176,4.186,4.183,4.189,4.205,4.208,4.215,4.217,4.226,4.234,4.250,4.252,4.259,4.269,4.277,4.293,4.305,4.314,4.332,4.347,3.596,3.449,3.323,3.254,3.202,3.186,3.168,3.162,3.150,3.153,3.142,3.144,3.158,3.180,3.300,3.384,4.600,4.618,4.645,4.668,4.688,4.706,4.731,4.748,4.773,4.795,4.824,4.852,4.879,4.903,4.935,4.959,4.983,5.012,5.043,5.078,5.106,5.143,5.161,5.229,5.265,5.290,5.320,5.365,5.410,5.432,2.534,2.580,5.482,5.457,5.621,6.126,6.170,6.221,6.261,6.315,6.368,6.425},Reflectance=[181]{40.000,42.000,44.000,38.000,44.000,46.000,45.000,43.000,50.000,47.000,42.000,47.000,45.000,44.000,43.000,44.000,45.000,44.000,48.000,47.000,46.000,46.000,45.000,41.000,41.000,46.000,49.000,52.000,46.000,48.000,48.000,45.000,50.000,52.000,51.000,50.000,42.000,46.000,54.000,47.000,46.000,48.000,49.000,55.000,53.000,49.000,45.000,38.000,37.000,60.000,47.000,40.000,46.000,47.000,41.000,46.000,55.000,58.000,47.000,57.000,57.000,52.000,56.000,58.000,50.000,52.000,49.000,48.000,48.000,58.000,57.000,50.000,47.000,40.000,59.000,74.000,76.000,74.000,72.000,75.000,75.000,75.000,74.000,71.000,69.000,70.000,67.000,67.000,72.000,75.000,78.000,76.000,77.000,78.000,79.000,79.000,79.000,79.000,78.000,80.000,79.000,79.000,80.000,79.000,79.000,78.000,80.000,80.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,80.000,101.000,105.000,102.000,85.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,77.000,76.000,74.000,98.000,111.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,76.000,77.000,75.000,75.000,76.000,77.000,70.000,69.000,71.000,71.000,67.000,62.000,62.000,59.000,28.000,9.000,58.000,58.000,65.000,69.000,72.000,71.000,67.000,67.000,67.000,68.000}
-63.883 DESIRED_THRUST iJoystick 87.6338999603
-63.883 DESIRED_RUDDER iJoystick 0
-63.871 LMS_LASER_2D_RIGHT LMS2 ID=4068,time=1225719875.521250,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=157,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.902,18.146,15.284,12.492,10.608,9.584,8.813,7.987,7.207,6.669,6.172,5.716,5.363,5.015,4.757,4.455,4.228,3.776,3.724,3.586,3.420,3.238,3.106,2.982,2.864,2.711,2.636,2.534,2.444,2.354,2.312,2.216,2.134,2.095,2.036,1.977,1.927,1.881,1.820,1.783,1.729,1.680,1.653,1.605,1.579,1.545,1.518,1.487,1.457,1.421,1.379,1.364,1.357,1.340,1.322,1.302,1.275,1.248,1.230,1.206,1.184,1.176,1.168,1.157,1.163,1.163,1.155,1.169,1.172,1.179,1.175,1.144,1.132,1.123,1.119,1.110,1.102,1.100,1.093,1.081,1.075,1.069,1.045,1.007,1.001,1.001,1.009,1.003,0.972,0.958,0.962,0.948},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,58.000,14.000,118.000,109.000,84.000,64.000,55.000,56.000,55.000,64.000,66.000,68.000,68.000,68.000,70.000,71.000,70.000,77.000,72.000,77.000,77.000,79.000,80.000,80.000,80.000,77.000,81.000,81.000,81.000,80.000,81.000,80.000,72.000,80.000,80.000,80.000,80.000,79.000,73.000,78.000,78.000,79.000,79.000,78.000,78.000,79.000,79.000,77.000,76.000,70.000,73.000,75.000,75.000,70.000,70.000,66.000,59.000,59.000,59.000,67.000,73.000,73.000,73.000,70.000,65.000,60.000,56.000,47.000,40.000,41.000,46.000,54.000,57.000,60.000,55.000,58.000,58.000,57.000,54.000,53.000,50.000,44.000,40.000,33.000,36.000,36.000,35.000,34.000,27.000,26.000,29.000,26.000}
-63.882 LMS_LASER_2D_LEFT LMS1 ID=4196,time=1225719875.529075,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=193,Range=[181]{1.047,1.051,1.053,1.068,1.077,1.080,1.095,1.098,1.112,1.117,1.131,1.136,1.153,1.170,1.182,1.193,1.208,1.217,1.227,1.236,1.247,1.273,1.284,1.293,1.319,1.334,1.357,1.374,1.389,1.410,1.424,1.455,1.475,1.504,1.532,1.552,1.591,1.599,1.623,1.652,1.692,1.724,1.747,1.778,1.800,1.844,1.868,1.925,1.958,1.987,2.039,2.079,2.129,2.177,2.249,2.298,2.345,2.408,2.488,2.555,2.595,2.615,2.621,2.676,2.835,2.870,2.927,2.995,3.069,3.174,3.249,3.352,3.513,3.686,3.820,3.859,3.920,3.946,3.944,3.967,4.004,4.015,4.018,4.020,4.020,4.041,4.021,4.032,4.077,4.116,4.119,4.113,4.148,4.149,4.158,4.161,4.161,4.161,4.159,4.161,4.164,4.167,4.173,4.176,4.184,4.184,4.194,4.192,4.202,4.211,4.218,4.224,4.232,4.242,4.251,4.260,4.269,4.278,4.284,4.294,4.317,4.323,4.344,4.340,3.615,3.352,3.344,3.247,3.191,3.175,3.159,3.153,3.147,3.143,3.142,3.145,3.156,3.179,3.282,3.377,4.616,4.642,4.660,4.679,4.707,4.732,4.750,4.774,4.798,4.827,4.849,4.870,4.900,4.928,4.950,4.973,5.009,5.040,5.070,5.100,5.131,5.167,5.225,5.262,5.288,5.323,5.365,2.589,2.533,2.510,2.513,2.506,2.540,5.598,6.171,6.209,6.256,6.305,6.350,6.402,6.445},Reflectance=[181]{41.000,43.000,44.000,43.000,44.000,50.000,49.000,45.000,49.000,47.000,46.000,48.000,48.000,44.000,45.000,43.000,42.000,34.000,43.000,48.000,49.000,44.000,46.000,46.000,46.000,48.000,46.000,46.000,49.000,47.000,50.000,48.000,49.000,45.000,42.000,44.000,40.000,54.000,53.000,46.000,42.000,40.000,44.000,50.000,52.000,44.000,46.000,40.000,39.000,50.000,42.000,49.000,52.000,46.000,42.000,49.000,51.000,51.000,51.000,57.000,70.000,60.000,55.000,58.000,47.000,55.000,46.000,47.000,48.000,55.000,57.000,49.000,48.000,42.000,57.000,75.000,75.000,73.000,72.000,74.000,75.000,76.000,74.000,72.000,70.000,71.000,68.000,68.000,71.000,74.000,78.000,76.000,76.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,80.000,79.000,79.000,79.000,81.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,101.000,8.000,105.000,84.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,77.000,75.000,74.000,91.000,111.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,76.000,76.000,75.000,76.000,77.000,76.000,71.000,68.000,71.000,70.000,67.000,62.000,25.000,56.000,69.000,55.000,30.000,14.000,58.000,67.000,68.000,68.000,63.000,63.000,63.000,66.000}
-63.894 LMS_LASER_2D_RIGHT LMS2 ID=4069,time=1225719875.534594,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=158,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.047,18.323,15.316,12.485,10.714,9.594,8.813,8.004,7.240,6.652,6.162,5.723,5.371,5.007,4.757,4.481,4.219,3.990,3.778,3.599,3.424,3.218,3.097,2.982,2.843,2.712,2.655,2.542,2.452,2.372,2.311,2.198,2.126,2.084,2.036,1.975,1.927,1.881,1.832,1.785,1.729,1.680,1.653,1.596,1.579,1.553,1.508,1.476,1.448,1.421,1.385,1.369,1.344,1.333,1.330,1.302,1.283,1.264,1.232,1.206,1.184,1.175,1.158,1.157,1.159,1.161,1.163,1.174,1.174,1.180,1.171,1.146,1.127,1.114,1.111,1.102,1.096,1.098,1.098,1.089,1.082,1.069,1.050,1.034,1.009,1.002,1.002,0.983,0.991,1.002,0.996,0.955},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,28.000,23.000,116.000,110.000,81.000,64.000,55.000,56.000,54.000,64.000,66.000,67.000,67.000,69.000,70.000,69.000,70.000,73.000,75.000,76.000,75.000,81.000,80.000,80.000,82.000,77.000,81.000,80.000,81.000,80.000,81.000,77.000,73.000,80.000,80.000,79.000,80.000,79.000,77.000,79.000,78.000,79.000,79.000,78.000,78.000,79.000,78.000,77.000,76.000,70.000,70.000,73.000,74.000,73.000,69.000,67.000,63.000,58.000,60.000,67.000,72.000,71.000,72.000,69.000,61.000,55.000,52.000,40.000,34.000,40.000,48.000,60.000,62.000,60.000,59.000,64.000,67.000,61.000,53.000,49.000,50.000,44.000,47.000,43.000,35.000,37.000,37.000,30.000,31.000,44.000,38.000,27.000}
-63.906 LMS_LASER_2D_RIGHT LMS2 ID=4070,time=1225719875.547936,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=159,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.124,18.403,15.338,12.566,10.751,9.629,8.834,8.013,7.240,6.696,6.154,5.732,5.371,4.998,4.766,4.473,4.229,3.990,3.793,3.607,3.413,3.213,3.104,2.975,2.865,2.722,2.656,2.552,2.461,2.388,2.310,2.209,2.148,2.086,2.028,1.977,1.911,1.873,1.829,1.786,1.725,1.689,1.660,1.606,1.586,1.554,1.518,1.466,1.451,1.428,1.393,1.369,1.360,1.344,1.330,1.294,1.286,1.261,1.230,1.207,1.191,1.174,1.151,1.149,1.162,1.156,1.162,1.177,1.168,1.171,1.178,1.160,1.123,1.117,1.114,1.106,1.102,1.103,1.097,1.088,1.072,1.065,1.048,1.034,1.009,1.003,1.003,0.984,0.999,1.001,0.996,0.950},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,28.000,26.000,121.000,109.000,82.000,63.000,56.000,56.000,54.000,64.000,66.000,67.000,67.000,70.000,71.000,70.000,72.000,74.000,77.000,75.000,77.000,79.000,80.000,80.000,81.000,80.000,81.000,81.000,81.000,80.000,80.000,77.000,78.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,79.000,78.000,76.000,78.000,79.000,79.000,77.000,74.000,67.000,69.000,77.000,77.000,74.000,67.000,69.000,67.000,61.000,63.000,68.000,70.000,70.000,73.000,71.000,63.000,56.000,51.000,41.000,34.000,35.000,43.000,54.000,60.000,62.000,56.000,60.000,63.000,59.000,52.000,49.000,49.000,46.000,47.000,43.000,36.000,37.000,37.000,31.000,33.000,55.000,49.000,27.000}
-63.907 DESIRED_THRUST iJoystick 87.6338999603
-63.907 DESIRED_RUDDER iJoystick 0
-63.908 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{5.9874,20.0409,-0.9357},Vel=[3x1]{-0.8123,-0.5986,6.7949},Raw=[2x1]{22.3156,-0.9357},time=1225719875.55549120903015,Speed=1.00902426915102,Pitch=0.04486707467677,Roll=0.03589365974142,PitchDot=-0.09197750308738,RollDot=-0.00017946829871
-63.908 ODOMETRY_POSE iPlatform Pose=[3x1]{5.9874,20.0409,-0.9348},Vel=[3x1]{-0.8123,-0.5986,0.5135},Raw=[2x1]{22.3156,-0.9357},time=1225719875.5555,Speed=1.0090,Pitch=-0.0023,Roll=0.0574,PitchDot=-0.0803,RollDot=0.0450
-63.627 MOOS_DEBUG uWatchdog Variable GPS has not appeared in more than 5 seconds.
-
-63.627 MOOS_DEBUG uWatchdog Variable ICAMERA_STATUS has not appeared in more than 5 seconds.
-
-63.627 MOOS_DEBUG uWatchdog Watchdog reports an error!
-63.894 LMS_LASER_2D_LEFT LMS1 ID=4197,time=1225719875.542411,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=194,Range=[181]{1.047,1.053,1.051,1.074,1.073,1.085,1.090,1.098,1.109,1.122,1.132,1.144,1.148,1.166,1.174,1.193,1.195,1.191,1.233,1.236,1.257,1.277,1.285,1.299,1.317,1.338,1.356,1.369,1.392,1.406,1.434,1.445,1.472,1.504,1.530,1.559,1.575,1.581,1.603,1.646,1.685,1.721,1.756,1.776,1.805,1.840,1.876,1.922,1.961,1.998,2.034,2.088,2.108,2.182,2.243,2.277,2.315,2.426,2.491,2.544,2.603,2.601,2.622,2.676,2.827,2.880,2.919,2.978,3.060,3.152,3.275,3.354,3.489,3.684,3.817,3.876,3.925,3.942,3.940,3.964,3.995,4.014,4.017,4.014,4.015,4.040,4.013,4.023,4.074,4.103,4.120,4.111,4.143,4.147,4.157,4.159,4.152,4.163,4.158,4.164,4.161,4.173,4.170,4.170,4.182,4.178,4.188,4.188,4.204,4.202,4.213,4.225,4.226,4.243,4.246,4.252,4.269,4.276,4.283,4.294,4.312,4.324,4.341,4.349,3.570,3.634,3.572,3.337,3.280,3.196,3.165,3.160,3.149,3.135,3.137,3.131,3.135,3.149,3.163,3.255,3.367,4.634,4.662,4.678,4.698,4.722,4.748,4.775,4.789,4.816,4.844,4.868,4.907,4.925,4.952,4.974,5.009,5.037,5.066,5.097,5.133,5.159,5.217,5.259,2.695,2.657,2.596,2.555,2.506,2.488,2.483,2.495,2.492,5.628,6.214,6.287,6.341,6.400,6.443,6.480,6.533},Reflectance=[181]{45.000,44.000,48.000,42.000,46.000,40.000,46.000,45.000,43.000,41.000,42.000,43.000,46.000,42.000,46.000,43.000,32.000,29.000,45.000,51.000,46.000,45.000,46.000,48.000,44.000,41.000,45.000,48.000,46.000,46.000,45.000,51.000,48.000,45.000,38.000,43.000,55.000,64.000,56.000,51.000,43.000,43.000,38.000,46.000,42.000,45.000,45.000,37.000,41.000,43.000,40.000,49.000,55.000,49.000,43.000,55.000,56.000,39.000,52.000,56.000,70.000,69.000,55.000,58.000,47.000,48.000,47.000,47.000,48.000,53.000,49.000,50.000,49.000,43.000,59.000,68.000,74.000,74.000,71.000,73.000,75.000,76.000,74.000,73.000,71.000,71.000,68.000,68.000,72.000,73.000,78.000,75.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,80.000,79.000,78.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,101.000,102.000,103.000,98.000,96.000,79.000,78.000,79.000,80.000,79.000,79.000,78.000,77.000,76.000,75.000,88.000,111.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,76.000,74.000,75.000,76.000,77.000,72.000,68.000,70.000,20.000,46.000,59.000,72.000,75.000,75.000,76.000,75.000,63.000,53.000,66.000,64.000,61.000,60.000,60.000,62.000,62.000}
-63.918 LMS_LASER_2D_LEFT LMS1 ID=4198,time=1225719875.555757,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=195,Range=[181]{1.047,1.054,1.058,1.071,1.082,1.089,1.089,1.098,1.115,1.122,1.129,1.140,1.157,1.166,1.177,1.192,1.203,1.220,1.229,1.232,1.253,1.271,1.286,1.305,1.327,1.333,1.346,1.374,1.387,1.403,1.430,1.451,1.479,1.508,1.524,1.565,1.565,1.583,1.603,1.652,1.680,1.715,1.747,1.779,1.816,1.838,1.863,1.907,1.954,1.988,2.030,2.079,2.119,2.176,2.231,2.288,2.352,2.426,2.493,2.547,2.589,2.599,2.619,2.665,2.820,2.864,2.904,2.979,3.046,3.144,3.278,3.355,3.499,3.643,3.812,3.879,3.942,3.935,3.939,3.964,3.997,4.007,4.012,4.013,4.016,4.032,4.017,4.021,4.066,4.105,4.114,4.112,4.143,4.143,4.148,4.163,4.152,4.152,4.154,4.163,4.158,4.166,4.167,4.168,4.174,4.186,4.184,4.196,4.202,4.200,4.209,4.217,4.225,4.234,4.244,4.252,4.268,4.275,4.284,4.295,4.313,4.323,4.331,4.341,3.478,3.616,3.437,3.369,3.459,3.295,3.193,3.166,3.150,3.147,3.137,3.132,3.130,3.135,3.138,3.153,3.251,3.368,4.654,4.680,4.696,4.721,4.746,4.764,4.787,4.815,4.837,4.869,4.902,4.928,4.942,4.966,5.007,5.039,5.056,5.097,5.123,5.156,5.216,2.701,2.649,2.595,2.559,2.528,2.496,2.469,2.465,2.474,2.480,2.499,2.548,6.343,6.393,6.448,6.498,6.552,6.609},Reflectance=[181]{45.000,41.000,43.000,37.000,42.000,41.000,46.000,45.000,45.000,40.000,44.000,45.000,45.000,46.000,48.000,42.000,43.000,39.000,48.000,46.000,43.000,43.000,45.000,38.000,36.000,48.000,50.000,45.000,48.000,48.000,48.000,46.000,42.000,40.000,34.000,38.000,54.000,58.000,56.000,54.000,45.000,37.000,44.000,42.000,43.000,46.000,48.000,49.000,42.000,53.000,45.000,46.000,55.000,50.000,47.000,52.000,45.000,43.000,53.000,50.000,69.000,66.000,57.000,57.000,48.000,56.000,55.000,51.000,50.000,58.000,47.000,46.000,50.000,49.000,57.000,66.000,74.000,72.000,71.000,73.000,76.000,76.000,75.000,73.000,71.000,71.000,69.000,68.000,70.000,74.000,76.000,76.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,81.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,89.000,102.000,94.000,11.000,107.000,101.000,80.000,78.000,79.000,79.000,79.000,79.000,78.000,77.000,75.000,74.000,90.000,111.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,75.000,78.000,77.000,76.000,75.000,74.000,74.000,76.000,76.000,71.000,68.000,50.000,72.000,75.000,75.000,77.000,78.000,77.000,79.000,79.000,75.000,61.000,42.000,58.000,57.000,54.000,57.000,58.000,61.000}
-63.930 LMS_LASER_2D_LEFT LMS1 ID=4199,time=1225719875.569102,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=196,Range=[181]{1.046,1.053,1.063,1.065,1.072,1.088,1.095,1.098,1.112,1.124,1.135,1.143,1.152,1.167,1.174,1.193,1.199,1.210,1.218,1.233,1.251,1.266,1.276,1.299,1.320,1.333,1.346,1.363,1.391,1.405,1.426,1.454,1.482,1.500,1.522,1.556,1.579,1.590,1.624,1.645,1.674,1.712,1.745,1.768,1.799,1.840,1.866,1.905,1.941,1.982,2.017,2.068,2.118,2.166,2.226,2.268,2.319,2.417,2.472,2.534,2.590,2.599,2.625,2.682,2.797,2.863,2.896,2.970,3.036,3.145,3.259,3.354,3.464,3.610,3.797,3.857,3.939,3.932,3.933,3.957,3.996,4.005,4.010,4.014,4.011,4.032,4.015,4.013,4.058,4.101,4.114,4.103,4.131,4.140,4.147,4.159,4.149,4.149,4.155,4.154,4.155,4.159,4.156,4.166,4.175,4.178,4.186,4.186,4.194,4.200,4.205,4.216,4.224,4.240,4.243,4.252,4.261,4.266,4.283,4.293,4.307,4.314,4.335,3.524,3.447,3.670,3.525,4.392,4.401,4.420,3.322,3.242,3.164,3.157,3.142,3.133,3.123,3.122,3.127,3.130,3.147,3.236,3.354,4.670,4.688,4.713,4.735,4.754,4.781,4.805,4.833,4.859,4.895,4.927,4.941,4.968,4.993,5.027,5.062,5.090,5.114,2.836,2.723,2.668,2.615,2.580,2.555,2.520,2.496,2.480,2.463,2.458,2.460,2.484,2.503,2.543,6.439,6.494,6.550,6.601,6.638},Reflectance=[181]{45.000,44.000,41.000,42.000,41.000,40.000,44.000,46.000,44.000,42.000,38.000,43.000,43.000,42.000,45.000,43.000,46.000,47.000,51.000,46.000,42.000,46.000,46.000,44.000,41.000,43.000,50.000,49.000,46.000,49.000,45.000,42.000,39.000,44.000,34.000,35.000,44.000,46.000,46.000,51.000,48.000,43.000,42.000,46.000,43.000,45.000,46.000,48.000,48.000,51.000,48.000,48.000,55.000,49.000,44.000,55.000,47.000,43.000,52.000,56.000,63.000,63.000,56.000,62.000,57.000,55.000,51.000,47.000,52.000,50.000,47.000,46.000,45.000,46.000,58.000,67.000,71.000,71.000,69.000,74.000,75.000,75.000,75.000,73.000,72.000,71.000,69.000,68.000,70.000,72.000,76.000,76.000,76.000,78.000,78.000,79.000,78.000,79.000,80.000,79.000,80.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,102.000,91.000,100.000,103.000,78.000,78.000,78.000,108.000,90.000,77.000,78.000,79.000,79.000,79.000,78.000,77.000,75.000,75.000,88.000,113.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,76.000,78.000,77.000,77.000,77.000,76.000,76.000,77.000,76.000,24.000,55.000,75.000,76.000,76.000,77.000,77.000,78.000,78.000,78.000,79.000,77.000,77.000,72.000,48.000,54.000,59.000,61.000,62.000,59.000}
-63.931 DESIRED_THRUST iJoystick 87.6338999603
-63.931 DESIRED_RUDDER iJoystick 0
-63.943 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.0209,20.0655,-0.9367},Vel=[3x1]{-0.8164,-0.6004,8.7179},Raw=[2x1]{22.3572,-0.9367},time=1225719875.59066724777222,Speed=1.01340498233112,Pitch=0.04038036720910,Roll=0.03589365974142,PitchDot=-0.06730061201516,RollDot=-0.00130114516563
-63.943 ODOMETRY_POSE iPlatform Pose=[3x1]{6.0209,20.0655,-0.9358},Vel=[3x1]{-0.8164,-0.6004,2.4336},Raw=[2x1]{22.3572,-0.9367},time=1225719875.5907,Speed=1.0134,Pitch=-0.0050,Roll=0.0538,PitchDot=0.0503,RollDot=0.0447
-63.944 LMS_LASER_2D_LEFT LMS1 ID=4200,time=1225719875.582448,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=197,Range=[181]{1.038,1.050,1.060,1.057,1.072,1.078,1.093,1.106,1.107,1.118,1.139,1.136,1.151,1.164,1.173,1.188,1.203,1.212,1.228,1.234,1.248,1.264,1.282,1.288,1.312,1.334,1.348,1.360,1.384,1.402,1.421,1.451,1.471,1.503,1.518,1.543,1.580,1.599,1.610,1.642,1.672,1.700,1.731,1.776,1.800,1.840,1.854,1.906,1.938,1.975,2.011,2.065,2.100,2.157,2.221,2.261,2.304,2.397,2.460,2.534,2.597,2.621,2.622,2.682,2.764,2.855,2.891,2.953,3.018,3.090,3.245,3.352,3.449,3.577,3.758,3.837,3.929,3.929,3.929,3.949,3.985,3.997,4.005,4.008,4.004,4.024,4.017,4.004,4.047,4.091,4.112,4.105,4.123,4.141,4.149,4.147,4.150,4.150,4.149,4.152,4.154,4.157,4.165,4.165,4.166,4.176,4.176,4.188,4.186,4.206,4.204,4.215,4.218,4.223,4.233,4.243,4.252,4.270,4.272,4.293,4.295,4.311,4.332,3.497,3.687,4.358,4.376,4.381,4.402,4.410,4.429,3.419,3.277,3.204,3.155,3.149,3.122,3.115,3.114,3.112,3.123,3.134,3.226,3.355,4.686,4.703,4.728,4.751,4.780,4.796,4.824,4.851,4.872,4.919,4.939,4.966,3.097,3.059,5.056,5.077,2.844,2.875,2.714,2.652,2.609,2.573,2.551,2.522,2.508,2.489,2.479,2.471,2.468,2.473,2.479,2.503,2.518,2.670,6.581,6.643,6.686},Reflectance=[181]{53.000,43.000,39.000,47.000,45.000,44.000,43.000,45.000,46.000,48.000,41.000,44.000,43.000,35.000,46.000,44.000,43.000,40.000,43.000,47.000,44.000,44.000,44.000,47.000,45.000,43.000,46.000,43.000,46.000,43.000,43.000,38.000,36.000,40.000,35.000,33.000,37.000,45.000,47.000,50.000,47.000,47.000,46.000,40.000,44.000,45.000,48.000,43.000,47.000,48.000,49.000,50.000,55.000,50.000,45.000,55.000,51.000,42.000,47.000,52.000,56.000,55.000,59.000,64.000,58.000,55.000,49.000,47.000,56.000,57.000,48.000,49.000,48.000,48.000,62.000,74.000,71.000,71.000,68.000,74.000,75.000,76.000,75.000,74.000,73.000,71.000,69.000,68.000,70.000,72.000,76.000,76.000,76.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,80.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,77.000,78.000,79.000,78.000,79.000,102.000,99.000,78.000,78.000,77.000,78.000,78.000,78.000,109.000,101.000,82.000,77.000,78.000,78.000,78.000,78.000,78.000,76.000,74.000,87.000,114.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,78.000,77.000,75.000,76.000,76.000,15.000,27.000,77.000,75.000,55.000,105.000,75.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,75.000,57.000,3.000,60.000,61.000,62.000}
-63.955 DESIRED_THRUST iJoystick 87.6338999603
-63.955 DESIRED_RUDDER iJoystick 0
-63.875 PLOGSTEREO_STATUS pLogStereo Frame= 1224, ImageFrame= 001225, last grab 49ms ago, CaptureRate= 20.0, LogRate= 20.0, GrowthRate=-0.0, DroppedFrames= 0, WrittenFrames= 1223, 1 Frames Pending, DroppingEvery= 0 ,AppErrorFlag=false,Uptime=-1545.53,MOOSName=pLogStereo,Publishing=MOOS_DEBUG,PLOGSTEREO_STATUS,Subscribing=LOGGER_RESTART,PLOGSTEREO_CMD,
-63.979 DESIRED_THRUST iJoystick 87.6338999603
-63.979 DESIRED_RUDDER iJoystick 0
-63.979 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.0456,20.0837,-0.9393},Vel=[3x1]{-0.8097,-0.5923,10.0000},Raw=[2x1]{22.3879,-0.9393},time=1225719875.62657928466797,Speed=1.00318331824421,Pitch=0.03813701347526,Roll=0.03140695227374,PitchDot=-0.08524744188587,RollDot=-0.00186198359909
-63.979 ODOMETRY_POSE iPlatform Pose=[3x1]{6.0456,20.0837,-0.9386},Vel=[3x1]{-0.8097,-0.5923,-2.5647},Raw=[2x1]{22.3879,-0.9393},time=1225719875.6266,Speed=1.0032,Pitch=-0.0028,Roll=0.0493,PitchDot=0.0725,RollDot=-0.0449
-64.003 DESIRED_THRUST iJoystick 87.6338999603
-64.003 DESIRED_RUDDER iJoystick 0
-64.015 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.0787,20.1077,-0.9443},Vel=[3x1]{-0.8304,-0.6010,8.0769},Raw=[2x1]{22.4288,-0.9443},time=1225719875.66247630119324,Speed=1.02508688414474,Pitch=0.03813701347526,Roll=0.02467689107222,PitchDot=-0.03813701347526,RollDot=-0.00179468298707
-64.015 ODOMETRY_POSE iPlatform Pose=[3x1]{6.0787,20.1077,-0.9439},Vel=[3x1]{-0.8304,-0.6010,1.7936},Raw=[2x1]{22.4288,-0.9443},time=1225719875.6625,Speed=1.0251,Pitch=0.0024,Roll=0.0454,PitchDot=0.0067,RollDot=0.0376
-64.027 DESIRED_THRUST iJoystick 86.60237434
-64.027 DESIRED_RUDDER iJoystick 0
-64.051 DESIRED_THRUST iJoystick 86.60237434
-64.051 DESIRED_RUDDER iJoystick 0
-64.051 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.1038,20.1258,-0.9484},Vel=[3x1]{-0.8566,-0.6147,8.7179},Raw=[2x1]{22.4597,-0.9484},time=1225719875.69854521751404,Speed=1.05429163867878,Pitch=0.03813701347526,Roll=0.01794682987071,PitchDot=-0.00673006120152,RollDot=-0.00235552142053
-64.051 ODOMETRY_POSE iPlatform Pose=[3x1]{6.1038,20.1258,-0.9482},Vel=[3x1]{-0.8566,-0.6147,2.4347},Raw=[2x1]{22.4597,-0.9484},time=1225719875.6985,Speed=1.0543,Pitch=0.0077,Roll=0.0414,PitchDot=0.0036,RollDot=0.0062
-64.075 DESIRED_THRUST iJoystick 85.5708487197
-64.075 DESIRED_RUDDER iJoystick 0
-64.087 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.1380,20.1502,-0.9534},Vel=[3x1]{-0.8383,-0.5951,6.0256},Raw=[2x1]{22.5017,-0.9534},time=1225719875.73447418212891,Speed=1.02800735959814,Pitch=0.03589365974142,Roll=0.00897341493535,PitchDot=-0.00224335373384,RollDot=-0.00195171774844
-64.087 ODOMETRY_POSE iPlatform Pose=[3x1]{6.1380,20.1502,-0.9535},Vel=[3x1]{-0.8383,-0.5951,-0.2576},Raw=[2x1]{22.5017,-0.9534},time=1225719875.7345,Speed=1.0280,Pitch=0.0135,Roll=0.0345,PitchDot=-0.0017,RollDot=-0.0025
-63.918 LMS_LASER_2D_RIGHT LMS2 ID=4071,time=1225719875.561278,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=160,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.354,-1.000,15.573,12.770,10.900,9.731,8.906,8.101,7.309,6.768,6.173,5.758,5.406,5.007,4.792,4.517,4.264,4.008,3.831,3.640,3.438,3.239,3.124,2.996,2.890,2.767,2.670,2.568,2.469,2.409,2.328,2.244,2.174,2.101,2.037,1.977,1.927,1.873,1.821,1.786,1.732,1.680,1.652,1.611,1.581,1.553,1.531,1.478,1.457,1.422,1.396,1.380,1.363,1.346,1.313,1.295,1.268,1.261,1.230,1.213,1.207,1.175,1.158,1.151,1.149,1.153,1.155,1.165,1.177,1.175,1.166,1.162,1.140,1.134,1.130,1.124,1.116,1.102,1.100,1.098,1.082,1.066,1.047,1.033,0.999,0.999,0.995,0.965,0.976,0.996,0.988,0.951},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,7.000,0.000,117.000,112.000,84.000,65.000,56.000,56.000,55.000,63.000,66.000,67.000,67.000,70.000,72.000,70.000,71.000,74.000,75.000,77.000,76.000,79.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,75.000,72.000,72.000,74.000,77.000,77.000,75.000,70.000,70.000,69.000,61.000,63.000,65.000,67.000,72.000,72.000,73.000,70.000,63.000,56.000,49.000,43.000,42.000,50.000,51.000,53.000,54.000,52.000,50.000,53.000,58.000,54.000,46.000,46.000,47.000,49.000,41.000,34.000,36.000,34.000,28.000,28.000,53.000,53.000,26.000}
-63.930 LMS_LASER_2D_RIGHT LMS2 ID=4072,time=1225719875.574617,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=161,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.710,-1.000,15.944,13.051,11.159,9.927,9.006,8.189,7.380,6.863,6.254,5.831,5.476,5.034,4.818,4.551,4.292,4.019,3.862,3.655,3.466,3.275,3.148,3.015,2.907,2.796,2.678,2.568,2.488,2.426,2.354,2.264,2.183,2.110,2.044,1.985,1.944,1.889,1.829,1.797,1.752,1.680,1.653,1.622,1.589,1.563,1.533,1.496,1.457,1.422,1.411,1.391,1.364,1.347,1.323,1.288,1.268,1.244,1.215,1.214,1.199,1.182,1.166,1.142,1.142,1.149,1.155,1.163,1.171,1.181,1.176,1.160,1.152,1.145,1.140,1.134,1.125,1.116,1.110,1.094,1.082,1.067,1.042,1.036,1.011,1.002,0.999,0.997,0.975,1.006,0.993,0.969},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,27.000,0.000,107.000,119.000,85.000,67.000,58.000,56.000,56.000,63.000,66.000,66.000,66.000,72.000,71.000,70.000,72.000,74.000,75.000,77.000,77.000,79.000,78.000,79.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,79.000,80.000,80.000,77.000,76.000,78.000,79.000,79.000,78.000,78.000,73.000,72.000,75.000,77.000,78.000,75.000,72.000,72.000,75.000,72.000,68.000,66.000,70.000,70.000,70.000,74.000,74.000,70.000,59.000,52.000,44.000,45.000,50.000,54.000,54.000,59.000,60.000,57.000,50.000,50.000,44.000,48.000,46.000,47.000,54.000,52.000,35.000,35.000,36.000,34.000,26.000,50.000,55.000,30.000}
-63.945 LMS_LASER_2D_RIGHT LMS2 ID=4073,time=1225719875.587959,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=162,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.583,13.352,11.543,10.159,9.174,8.333,7.546,6.978,6.400,5.928,5.552,5.087,4.890,4.596,4.339,4.067,3.905,3.708,3.501,3.342,3.178,3.037,2.923,2.821,2.698,2.605,2.498,2.444,2.371,2.274,2.200,2.130,2.061,2.003,1.954,1.910,1.830,1.803,1.768,1.694,1.661,1.634,1.596,1.563,1.535,1.506,1.472,1.431,1.420,1.396,1.380,1.354,1.323,1.297,1.280,1.262,1.243,1.226,1.201,1.197,1.174,1.159,1.144,1.150,1.153,1.169,1.176,1.177,1.175,1.176,1.172,1.159,1.141,1.133,1.125,1.107,1.110,1.100,1.092,1.070,1.053,1.047,1.020,0.997,0.999,1.007,0.985,1.001,0.999,0.982},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,88.000,129.000,86.000,70.000,61.000,56.000,56.000,61.000,65.000,66.000,66.000,73.000,70.000,71.000,72.000,75.000,75.000,77.000,76.000,78.000,79.000,75.000,80.000,80.000,81.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,75.000,72.000,79.000,78.000,79.000,79.000,78.000,75.000,73.000,76.000,77.000,77.000,75.000,72.000,73.000,73.000,72.000,72.000,72.000,73.000,75.000,70.000,73.000,74.000,72.000,63.000,51.000,41.000,36.000,38.000,41.000,40.000,50.000,57.000,57.000,53.000,53.000,51.000,50.000,43.000,48.000,52.000,53.000,37.000,34.000,36.000,38.000,29.000,35.000,34.000,33.000}
-63.958 LMS_LASER_2D_RIGHT LMS2 ID=4074,time=1225719875.601300,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=163,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.754,17.523,14.508,12.082,10.460,9.443,8.616,7.796,7.114,6.546,6.025,5.671,5.212,4.972,4.706,4.429,4.160,3.964,3.788,3.556,3.384,3.229,3.071,2.979,2.855,2.733,2.635,2.526,2.461,2.397,2.318,2.224,2.159,2.089,2.019,1.969,1.920,1.882,1.821,1.777,1.721,1.671,1.643,1.606,1.581,1.536,1.506,1.478,1.455,1.432,1.405,1.371,1.357,1.333,1.305,1.289,1.269,1.250,1.226,1.201,1.193,1.168,1.157,1.147,1.141,1.148,1.148,1.172,1.167,1.175,1.171,1.175,1.167,1.168,1.148,1.130,1.112,1.109,1.105,1.100,1.084,1.064,1.049,1.032,1.009,1.007,1.004,1.002,0.970,0.976,0.959},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,43.000,60.000,119.000,101.000,78.000,62.000,56.000,56.000,57.000,65.000,67.000,67.000,72.000,70.000,70.000,72.000,73.000,74.000,76.000,76.000,77.000,79.000,77.000,79.000,80.000,81.000,81.000,81.000,81.000,80.000,80.000,79.000,78.000,81.000,80.000,80.000,81.000,80.000,79.000,80.000,75.000,73.000,79.000,79.000,79.000,79.000,78.000,77.000,76.000,77.000,77.000,77.000,75.000,74.000,72.000,73.000,71.000,68.000,71.000,74.000,73.000,73.000,75.000,75.000,71.000,68.000,60.000,45.000,36.000,38.000,35.000,36.000,34.000,38.000,45.000,52.000,55.000,50.000,48.000,43.000,43.000,49.000,50.000,41.000,35.000,38.000,40.000,37.000,25.000,25.000,25.000}
-63.958 LMS_LASER_2D_RIGHT LMS2 ID=4075,time=1225719875.614628,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=164,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.996,18.159,15.388,12.646,10.628,9.740,8.877,8.074,7.283,6.732,6.154,5.785,5.407,5.024,4.791,4.518,4.239,4.017,3.848,3.616,3.429,3.275,3.117,2.993,2.890,2.780,2.671,2.588,2.488,2.409,2.344,2.255,2.157,2.113,2.044,1.985,1.936,1.894,1.838,1.803,1.730,1.679,1.642,1.610,1.579,1.553,1.521,1.490,1.472,1.443,1.405,1.372,1.360,1.342,1.309,1.294,1.279,1.258,1.226,1.209,1.191,1.168,1.152,1.151,1.134,1.148,1.151,1.166,1.172,1.171,1.179,1.178,1.159,1.157,1.141,1.144,1.112,1.108,1.111,1.103,1.088,1.078,1.063,1.038,1.008,0.998,1.014,1.007,0.974,0.973,0.977},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,50.000,16.000,120.000,110.000,90.000,63.000,55.000,55.000,54.000,64.000,66.000,66.000,68.000,70.000,71.000,71.000,73.000,74.000,75.000,75.000,77.000,79.000,78.000,78.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,75.000,80.000,80.000,80.000,80.000,81.000,79.000,79.000,76.000,72.000,79.000,77.000,78.000,79.000,77.000,78.000,78.000,77.000,74.000,75.000,76.000,76.000,75.000,75.000,72.000,67.000,72.000,72.000,71.000,73.000,74.000,77.000,74.000,68.000,62.000,50.000,37.000,37.000,36.000,33.000,31.000,32.000,31.000,44.000,55.000,53.000,48.000,42.000,42.000,40.000,45.000,38.000,33.000,36.000,40.000,38.000,28.000,26.000,30.000}
-63.983 LMS_LASER_2D_RIGHT LMS2 ID=4076,time=1225719875.627967,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=165,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.457,16.464,13.295,11.541,10.132,9.120,8.305,7.484,6.960,6.391,5.928,5.552,5.095,4.890,4.605,4.339,4.092,3.904,3.690,3.474,3.326,3.157,3.033,2.940,2.831,2.697,2.613,2.527,2.444,2.374,2.283,2.197,2.139,2.071,2.004,1.945,1.911,1.858,1.815,1.746,1.692,1.640,1.601,1.593,1.570,1.530,1.507,1.472,1.451,1.415,1.381,1.369,1.351,1.312,1.299,1.280,1.277,1.251,1.218,1.191,1.175,1.161,1.152,1.150,1.147,1.157,1.162,1.165,1.177,1.173,1.166,1.164,1.162,1.133,1.146,1.125,1.105,1.110,1.109,1.087,1.071,1.066,1.051,1.019,1.014,1.014,1.009,1.004,1.010,0.962},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,11.000,94.000,125.000,84.000,68.000,60.000,55.000,56.000,61.000,66.000,66.000,66.000,72.000,70.000,71.000,72.000,74.000,74.000,76.000,77.000,78.000,78.000,77.000,80.000,81.000,80.000,80.000,81.000,81.000,81.000,80.000,76.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,78.000,75.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,77.000,74.000,74.000,77.000,77.000,76.000,77.000,74.000,68.000,70.000,72.000,70.000,71.000,74.000,74.000,71.000,67.000,60.000,51.000,45.000,43.000,35.000,32.000,32.000,32.000,29.000,40.000,53.000,60.000,54.000,43.000,33.000,35.000,43.000,44.000,33.000,36.000,40.000,36.000,32.000,39.000,25.000}
-63.994 LMS_LASER_2D_RIGHT LMS2 ID=4077,time=1225719875.641304,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=166,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.420,17.354,14.410,12.037,10.460,9.434,8.607,7.796,7.097,6.538,6.035,5.671,5.229,4.972,4.698,4.421,4.194,3.955,3.760,3.557,3.389,3.213,3.071,2.975,2.864,2.755,2.654,2.561,2.470,2.399,2.319,2.237,2.157,2.095,2.027,1.969,1.929,1.884,1.832,1.779,1.719,1.645,1.597,1.592,1.575,1.538,1.512,1.476,1.457,1.431,1.387,1.370,1.357,1.329,1.312,1.289,1.271,1.253,1.226,1.200,1.182,1.168,1.151,1.157,1.154,1.159,1.170,1.169,1.179,1.184,1.174,1.168,1.159,1.158,1.152,1.126,1.111,1.105,1.118,1.100,1.085,1.073,1.053,1.035,1.003,1.014,1.014,1.020,1.014,1.009},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,16.000,65.000,116.000,100.000,75.000,62.000,56.000,56.000,57.000,65.000,67.000,67.000,70.000,69.000,70.000,72.000,73.000,74.000,77.000,77.000,79.000,79.000,77.000,80.000,80.000,81.000,81.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,76.000,73.000,74.000,77.000,75.000,75.000,78.000,76.000,73.000,73.000,72.000,71.000,71.000,72.000,73.000,69.000,65.000,61.000,51.000,44.000,41.000,38.000,34.000,31.000,31.000,34.000,43.000,54.000,63.000,56.000,43.000,36.000,41.000,36.000,40.000,35.000,34.000,38.000,36.000,35.000,46.000,41.000}
-64.006 LMS_LASER_2D_RIGHT LMS2 ID=4078,time=1225719875.654641,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=167,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.892,18.269,15.439,12.699,10.715,9.712,8.885,8.083,7.292,6.741,6.173,5.794,5.424,5.033,4.791,4.500,4.264,4.010,3.843,3.622,3.430,3.262,3.125,3.005,2.906,2.781,2.680,2.604,2.498,2.426,2.356,2.273,2.185,2.114,2.053,1.986,1.938,1.901,1.848,1.794,1.729,1.671,1.628,1.609,1.571,1.560,1.524,1.488,1.466,1.434,1.393,1.383,1.358,1.333,1.309,1.299,1.262,1.247,1.226,1.208,1.191,1.174,1.171,1.169,1.173,1.162,1.165,1.174,1.181,1.180,1.181,1.168,1.159,1.163,1.155,1.132,1.111,1.113,1.119,1.078,1.084,1.073,1.064,1.044,1.012,0.999,0.980,0.980,0.985,0.991},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,35.000,19.000,119.000,109.000,87.000,64.000,55.000,55.000,54.000,63.000,66.000,66.000,68.000,70.000,70.000,71.000,72.000,74.000,76.000,77.000,77.000,78.000,78.000,79.000,80.000,81.000,81.000,80.000,81.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,81.000,80.000,80.000,79.000,78.000,79.000,77.000,77.000,74.000,75.000,78.000,78.000,77.000,75.000,76.000,75.000,70.000,73.000,77.000,77.000,73.000,75.000,71.000,71.000,69.000,69.000,65.000,58.000,60.000,63.000,57.000,46.000,37.000,37.000,35.000,31.000,31.000,35.000,45.000,53.000,63.000,56.000,39.000,29.000,34.000,38.000,46.000,37.000,31.000,31.000,26.000,26.000,28.000,31.000}
-64.018 LMS_LASER_2D_RIGHT LMS2 ID=4079,time=1225719875.667975,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=168,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.291,13.151,11.411,10.097,9.137,8.330,7.519,6.967,6.391,5.928,5.552,5.113,4.899,4.588,4.340,4.100,3.916,3.695,3.492,3.325,3.183,3.053,2.947,2.829,2.724,2.634,2.541,2.451,2.382,2.293,2.227,2.148,2.086,2.010,1.962,1.928,1.864,1.812,1.754,1.722,1.666,1.632,1.590,1.560,1.530,1.506,1.475,1.441,1.401,1.389,1.367,1.349,1.320,1.303,1.282,1.255,1.238,1.226,1.209,1.199,1.181,1.178,1.176,1.163,1.171,1.184,1.182,1.181,1.185,1.170,1.176,1.159,1.157,1.134,1.112,1.125,1.113,1.100,1.058,1.072,1.071,1.054,1.016,0.979,1.002,1.005,0.978,0.972},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,100.000,122.000,88.000,68.000,59.000,55.000,56.000,61.000,66.000,66.000,67.000,72.000,69.000,71.000,73.000,74.000,75.000,78.000,77.000,78.000,78.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,78.000,78.000,74.000,76.000,77.000,78.000,77.000,74.000,78.000,77.000,69.000,69.000,75.000,75.000,74.000,74.000,74.000,71.000,72.000,70.000,67.000,63.000,57.000,64.000,60.000,42.000,40.000,45.000,38.000,33.000,32.000,31.000,38.000,54.000,64.000,53.000,35.000,33.000,28.000,32.000,40.000,40.000,31.000,28.000,32.000,31.000,27.000,26.000}
-64.031 LMS_LASER_2D_RIGHT LMS2 ID=4080,time=1225719875.681309,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=169,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.397,17.371,14.341,11.977,10.440,9.398,8.579,7.796,7.134,6.555,6.044,5.680,5.292,4.989,4.698,4.422,4.220,3.946,3.776,3.559,3.383,3.226,3.104,2.991,2.863,2.762,2.661,2.577,2.486,2.424,2.330,2.248,2.174,2.103,2.027,1.967,1.935,1.884,1.825,1.767,1.732,1.688,1.652,1.631,1.582,1.549,1.523,1.488,1.446,1.406,1.390,1.379,1.350,1.334,1.301,1.283,1.259,1.247,1.231,1.217,1.184,1.182,1.166,1.165,1.156,1.159,1.174,1.179,1.186,1.175,1.179,1.176,1.164,1.155,1.151,1.129,1.140,1.122,1.101,1.086,1.082,1.056,1.052,1.023,1.010,1.005,1.015,0.985,0.969},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,25.000,64.000,119.000,100.000,75.000,62.000,55.000,56.000,57.000,65.000,67.000,67.000,70.000,69.000,71.000,72.000,72.000,74.000,77.000,77.000,77.000,78.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,77.000,79.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,76.000,77.000,77.000,72.000,72.000,74.000,75.000,75.000,76.000,75.000,75.000,71.000,73.000,70.000,69.000,69.000,68.000,61.000,49.000,44.000,47.000,46.000,36.000,34.000,33.000,40.000,51.000,60.000,40.000,32.000,32.000,31.000,36.000,31.000,35.000,36.000,37.000,38.000,38.000,28.000,27.000}
-64.042 LMS_LASER_2D_RIGHT LMS2 ID=4081,time=1225719875.694641,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=170,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.652,18.416,15.507,12.751,10.808,9.740,8.887,8.127,7.333,6.785,6.200,5.812,5.476,5.085,4.808,4.526,4.300,4.005,3.874,3.648,3.447,3.281,3.148,3.029,2.912,2.796,2.698,2.613,2.523,2.442,2.347,2.276,2.212,2.128,2.053,1.983,1.935,1.907,1.829,1.790,1.759,1.715,1.671,1.643,1.603,1.567,1.533,1.497,1.469,1.427,1.390,1.390,1.366,1.342,1.315,1.290,1.266,1.258,1.236,1.226,1.209,1.184,1.175,1.166,1.157,1.156,1.161,1.174,1.176,1.183,1.176,1.182,1.177,1.168,1.154,1.150,1.144,1.134,1.125,1.084,1.088,1.079,1.065,1.040,1.015,1.012,1.013,1.005,0.979},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,15.000,12.000,120.000,110.000,87.000,64.000,56.000,56.000,54.000,63.000,66.000,66.000,67.000,70.000,70.000,72.000,72.000,75.000,76.000,77.000,77.000,78.000,78.000,81.000,79.000,80.000,81.000,80.000,80.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,79.000,77.000,75.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,75.000,75.000,77.000,75.000,74.000,73.000,74.000,75.000,75.000,73.000,71.000,72.000,73.000,72.000,69.000,70.000,67.000,58.000,49.000,50.000,46.000,34.000,33.000,36.000,43.000,45.000,47.000,36.000,43.000,43.000,30.000,34.000,35.000,42.000,38.000,36.000,37.000,38.000,32.000,27.000}
-64.055 LMS_LASER_2D_RIGHT LMS2 ID=4082,time=1225719875.707973,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=171,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.424,16.522,13.348,11.518,10.158,9.182,8.376,7.540,6.994,6.425,5.928,5.586,5.184,4.908,4.629,4.366,4.127,3.925,3.719,3.514,3.325,3.189,3.069,2.957,2.851,2.740,2.654,2.569,2.476,2.388,2.294,2.240,2.150,2.070,2.002,1.961,1.910,1.863,1.813,1.765,1.725,1.680,1.656,1.613,1.572,1.543,1.504,1.469,1.449,1.412,1.385,1.380,1.344,1.316,1.297,1.284,1.267,1.252,1.232,1.216,1.197,1.177,1.166,1.150,1.149,1.172,1.173,1.176,1.187,1.185,1.177,1.179,1.175,1.163,1.156,1.152,1.134,1.121,1.081,1.065,1.080,1.074,1.046,1.023,1.013,1.012,1.005,0.975},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,93.000,122.000,90.000,69.000,60.000,56.000,57.000,60.000,65.000,67.000,67.000,70.000,69.000,70.000,72.000,74.000,75.000,78.000,77.000,78.000,80.000,80.000,80.000,79.000,80.000,81.000,80.000,80.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,79.000,77.000,78.000,79.000,79.000,80.000,78.000,77.000,78.000,77.000,77.000,72.000,69.000,75.000,77.000,74.000,74.000,74.000,75.000,75.000,71.000,67.000,69.000,75.000,74.000,70.000,72.000,70.000,60.000,53.000,54.000,48.000,41.000,31.000,33.000,40.000,44.000,40.000,47.000,50.000,52.000,29.000,27.000,34.000,41.000,34.000,34.000,36.000,37.000,32.000,27.000}
-64.066 LMS_LASER_2D_RIGHT LMS2 ID=4083,time=1225719875.721302,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=172,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.381,17.217,14.233,11.982,10.454,9.426,8.622,7.788,7.125,6.563,6.018,5.681,5.328,5.006,4.706,4.438,4.239,3.993,3.800,3.590,3.361,3.210,3.103,2.999,2.869,2.778,2.679,2.588,2.505,2.414,2.321,2.266,2.145,2.082,2.019,1.967,1.928,1.875,1.829,1.775,1.732,1.698,1.672,1.632,1.571,1.535,1.522,1.488,1.466,1.429,1.405,1.375,1.355,1.324,1.309,1.286,1.273,1.252,1.225,1.209,1.193,1.184,1.167,1.150,1.156,1.160,1.176,1.182,1.182,1.179,1.175,1.171,1.176,1.163,1.150,1.149,1.125,1.125,1.113,1.075,1.067,1.082,1.053,1.023,1.015,1.007,1.016,1.027},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,20.000,71.000,119.000,98.000,74.000,63.000,55.000,56.000,58.000,66.000,68.000,69.000,69.000,69.000,70.000,71.000,72.000,75.000,76.000,78.000,78.000,78.000,79.000,80.000,79.000,80.000,80.000,81.000,80.000,80.000,81.000,81.000,82.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,80.000,78.000,74.000,76.000,78.000,78.000,76.000,70.000,74.000,75.000,75.000,74.000,75.000,76.000,74.000,71.000,69.000,72.000,74.000,72.000,71.000,71.000,68.000,62.000,54.000,49.000,35.000,33.000,32.000,32.000,34.000,37.000,31.000,50.000,58.000,53.000,37.000,28.000,29.000,36.000,37.000,34.000,34.000,38.000,41.000,37.000}
-64.090 LMS_LASER_2D_RIGHT LMS2 ID=4084,time=1225719875.734642,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=173,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.726,17.877,15.109,12.436,10.654,9.620,8.805,8.011,7.264,6.706,6.109,5.768,5.424,5.085,4.757,4.483,4.279,4.035,3.853,3.614,3.396,3.239,3.144,3.021,2.913,2.812,2.707,2.606,2.532,2.442,2.354,2.274,2.124,2.083,2.047,1.985,1.944,1.892,1.841,1.795,1.752,1.716,1.685,1.640,1.592,1.545,1.530,1.499,1.479,1.438,1.414,1.388,1.364,1.328,1.314,1.294,1.276,1.260,1.233,1.208,1.200,1.174,1.167,1.159,1.157,1.166,1.173,1.180,1.188,1.179,1.175,1.182,1.187,1.175,1.139,1.152,1.135,1.121,1.119,1.101,1.082,1.078,1.033,1.022,1.018,1.010,1.017,1.021},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,40.000,47.000,115.000,107.000,82.000,63.000,56.000,55.000,54.000,64.000,67.000,68.000,68.000,69.000,71.000,72.000,75.000,74.000,77.000,78.000,78.000,79.000,80.000,81.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,83.000,82.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,75.000,77.000,77.000,77.000,78.000,78.000,70.000,73.000,76.000,75.000,75.000,76.000,75.000,75.000,70.000,69.000,71.000,72.000,70.000,72.000,72.000,70.000,61.000,52.000,42.000,36.000,33.000,31.000,32.000,34.000,38.000,29.000,41.000,58.000,56.000,36.000,31.000,30.000,37.000,28.000,31.000,35.000,37.000,39.000,40.000}
-64.099 DESIRED_THRUST iJoystick 85.5708487197
-64.099 DESIRED_RUDDER iJoystick 0
-63.944 LMS_LASER_2D_LEFT LMS1 ID=4201,time=1225719875.595781,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=198,Range=[181]{1.012,1.039,1.053,1.064,1.073,1.074,1.082,1.098,1.101,1.111,1.125,1.139,1.145,1.162,1.169,1.182,1.191,1.208,1.221,1.232,1.247,1.268,1.271,1.286,1.315,1.324,1.339,1.366,1.378,1.398,1.414,1.428,1.464,1.496,1.520,1.544,1.567,1.596,1.606,1.643,1.654,1.691,1.731,1.758,1.790,1.834,1.858,1.883,1.922,1.962,2.002,2.045,2.082,2.127,2.195,2.250,2.287,2.382,2.454,2.531,2.592,2.630,2.622,2.635,2.735,2.836,2.885,2.930,3.009,3.078,3.176,3.329,3.439,3.565,3.685,3.812,3.894,3.925,3.928,3.936,3.975,3.996,4.008,4.010,4.000,4.011,4.015,4.000,4.034,4.071,4.107,4.108,4.113,4.138,4.146,4.149,4.149,4.147,4.139,4.152,4.150,4.155,4.158,4.156,4.173,4.173,4.175,4.175,4.183,4.194,4.196,4.207,4.208,4.224,4.233,4.241,4.243,4.252,4.265,4.286,4.292,4.304,4.319,4.331,3.631,4.349,4.367,4.384,4.392,4.402,4.421,4.438,4.451,3.376,3.277,3.179,3.139,3.130,3.114,3.104,3.104,3.106,3.117,3.183,3.332,4.694,4.721,4.743,4.763,4.788,4.811,4.841,4.866,4.898,4.925,4.949,4.976,3.042,2.916,2.976,2.817,2.767,2.715,2.668,2.627,2.592,2.568,2.539,2.523,2.507,2.489,2.482,2.475,2.477,2.474,2.481,2.492,2.509,2.554,6.687,6.747},Reflectance=[181]{58.000,54.000,44.000,46.000,45.000,47.000,47.000,45.000,48.000,44.000,42.000,40.000,44.000,44.000,43.000,45.000,45.000,45.000,44.000,46.000,44.000,45.000,48.000,45.000,43.000,43.000,45.000,45.000,43.000,41.000,32.000,32.000,33.000,34.000,37.000,35.000,34.000,39.000,46.000,45.000,47.000,47.000,44.000,40.000,43.000,43.000,50.000,53.000,48.000,50.000,49.000,46.000,54.000,55.000,47.000,55.000,55.000,43.000,43.000,45.000,54.000,50.000,55.000,66.000,64.000,51.000,50.000,48.000,50.000,52.000,52.000,58.000,48.000,50.000,52.000,71.000,68.000,72.000,68.000,72.000,74.000,75.000,76.000,75.000,72.000,70.000,69.000,67.000,69.000,71.000,74.000,77.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,80.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,99.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,110.000,101.000,81.000,78.000,78.000,78.000,78.000,78.000,76.000,74.000,82.000,110.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,30.000,42.000,118.000,77.000,75.000,76.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,76.000,65.000,40.000,50.000,53.000}
-63.958 LMS_LASER_2D_LEFT LMS1 ID=4202,time=1225719875.609114,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=199,Range=[181]{1.011,1.015,1.043,1.055,1.068,1.074,1.081,1.097,1.093,1.109,1.118,1.136,1.149,1.157,1.168,1.175,1.192,1.204,1.218,1.233,1.242,1.251,1.262,1.273,1.303,1.314,1.333,1.355,1.374,1.392,1.403,1.410,1.440,1.471,1.503,1.543,1.553,1.588,1.608,1.628,1.645,1.672,1.704,1.740,1.786,1.805,1.848,1.866,1.903,1.952,1.985,2.022,2.066,2.106,2.153,2.240,2.294,2.359,2.424,2.496,2.580,2.622,2.617,2.621,2.709,2.772,2.867,2.912,2.978,3.042,3.124,3.273,3.409,3.529,3.626,3.789,3.875,3.929,3.919,3.923,3.955,3.988,3.995,4.001,3.998,4.004,4.016,4.000,4.011,4.056,4.089,4.105,4.094,4.129,4.140,4.140,4.140,4.149,4.146,4.140,4.152,4.145,4.152,4.155,4.170,4.178,4.174,4.175,4.184,4.184,4.194,4.202,4.207,4.215,4.226,4.230,4.240,4.252,4.259,4.274,4.281,4.299,4.310,4.328,4.286,4.349,4.361,4.375,4.384,4.403,4.411,4.420,4.437,4.459,4.465,3.367,3.248,3.136,3.121,3.111,3.095,3.095,3.096,3.100,3.135,3.289,3.196,4.724,4.751,4.776,4.802,4.829,4.855,4.874,4.906,4.937,2.953,3.023,2.879,2.837,2.811,2.776,2.738,2.684,2.655,2.625,2.598,2.568,2.541,2.526,2.503,2.490,2.484,2.479,2.477,2.475,2.483,2.488,2.513,2.527,2.565},Reflectance=[181]{61.000,59.000,48.000,46.000,43.000,47.000,45.000,41.000,43.000,43.000,48.000,44.000,42.000,45.000,43.000,42.000,47.000,44.000,42.000,45.000,45.000,46.000,48.000,49.000,46.000,47.000,48.000,46.000,40.000,34.000,33.000,30.000,31.000,32.000,38.000,39.000,37.000,44.000,40.000,47.000,47.000,55.000,49.000,46.000,40.000,42.000,45.000,46.000,50.000,49.000,49.000,50.000,55.000,57.000,55.000,46.000,43.000,44.000,45.000,47.000,40.000,51.000,53.000,55.000,61.000,57.000,50.000,47.000,47.000,48.000,49.000,49.000,54.000,46.000,49.000,59.000,67.000,73.000,70.000,71.000,73.000,75.000,75.000,74.000,71.000,70.000,69.000,67.000,67.000,70.000,72.000,76.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,77.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,77.000,77.000,77.000,77.000,77.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,110.000,99.000,77.000,78.000,77.000,78.000,78.000,76.000,74.000,72.000,104.000,28.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,76.000,29.000,112.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,76.000,76.000,76.000,75.000,76.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,75.000,58.000,20.000}
-63.970 LMS_LASER_2D_LEFT LMS1 ID=4203,time=1225719875.622446,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=200,Range=[181]{1.007,1.003,1.016,1.052,1.062,1.075,1.081,1.089,1.068,1.122,1.115,1.111,1.135,1.141,1.166,1.174,1.177,1.207,1.208,1.219,1.236,1.248,1.271,1.278,1.294,1.312,1.336,1.344,1.369,1.394,1.406,1.407,1.427,1.479,1.496,1.521,1.551,1.577,1.594,1.627,1.650,1.660,1.674,1.724,1.769,1.804,1.840,1.865,1.897,1.941,1.976,2.022,2.052,2.087,2.135,2.212,2.263,2.336,2.397,2.467,2.562,2.612,2.609,2.603,2.669,2.790,2.844,2.898,2.954,3.024,3.101,3.215,3.376,3.494,3.574,3.735,3.838,3.905,3.926,3.915,3.942,3.975,3.991,3.993,3.992,3.998,4.016,4.002,4.004,4.038,4.080,4.102,4.095,4.114,4.128,4.130,4.145,4.140,4.143,4.139,4.141,4.145,4.145,4.147,4.162,4.177,4.178,4.178,4.187,4.186,4.183,4.191,4.198,4.208,4.217,4.222,4.241,4.249,4.258,4.268,4.284,4.293,4.301,4.319,4.328,4.347,4.347,4.367,4.375,4.392,4.402,4.412,4.430,4.448,4.466,4.482,4.498,3.284,3.196,3.119,3.101,3.085,3.086,3.081,3.091,3.125,3.246,3.344,4.740,4.771,4.787,4.812,4.838,4.868,4.892,2.988,2.972,2.899,2.864,2.838,2.814,2.788,2.765,2.727,2.688,2.660,2.640,2.618,2.609,2.588,2.557,2.501,2.503,2.486,2.483,2.475,2.480,2.483,2.490,2.500,2.514},Reflectance=[181]{59.000,64.000,55.000,49.000,46.000,47.000,45.000,41.000,31.000,40.000,50.000,56.000,48.000,47.000,45.000,45.000,48.000,45.000,46.000,43.000,43.000,44.000,43.000,47.000,45.000,45.000,44.000,44.000,43.000,36.000,37.000,31.000,28.000,35.000,42.000,38.000,39.000,43.000,42.000,41.000,39.000,58.000,55.000,54.000,45.000,45.000,45.000,44.000,48.000,52.000,49.000,50.000,56.000,60.000,55.000,46.000,49.000,42.000,50.000,50.000,44.000,46.000,58.000,59.000,51.000,46.000,47.000,49.000,47.000,47.000,47.000,46.000,48.000,48.000,46.000,58.000,71.000,71.000,70.000,69.000,74.000,74.000,76.000,75.000,72.000,71.000,69.000,67.000,68.000,70.000,72.000,75.000,76.000,76.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,79.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,77.000,107.000,86.000,77.000,77.000,77.000,78.000,76.000,74.000,74.000,91.000,112.000,75.000,77.000,77.000,77.000,76.000,78.000,77.000,48.000,84.000,78.000,78.000,78.000,78.000,79.000,77.000,77.000,76.000,75.000,75.000,74.000,69.000,60.000,54.000,67.000,75.000,77.000,79.000,79.000,80.000,78.000,78.000,76.000,70.000}
-63.983 LMS_LASER_2D_LEFT LMS1 ID=4204,time=1225719875.635778,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=201,Range=[181]{1.022,1.003,1.003,1.029,1.051,1.065,1.069,1.087,1.068,1.085,1.105,1.104,1.106,1.139,1.157,1.158,1.182,1.187,1.202,1.214,1.228,1.240,1.259,1.267,1.282,1.312,1.318,1.336,1.355,1.381,1.405,1.397,1.421,1.476,1.482,1.503,1.528,1.565,1.577,1.607,1.635,1.660,1.690,1.710,1.732,1.782,1.808,1.839,1.878,1.918,1.958,2.005,2.033,2.066,2.115,2.182,2.250,2.313,2.371,2.440,2.522,2.605,2.612,2.590,2.616,2.735,2.802,2.865,2.934,2.994,3.075,3.164,3.265,3.440,3.538,3.665,3.811,3.913,3.910,3.907,3.922,3.958,3.990,3.996,3.996,3.995,3.993,3.998,3.990,4.021,4.060,4.090,4.091,4.102,4.121,4.131,4.134,4.143,4.143,4.140,4.132,4.141,4.140,4.149,4.152,4.158,4.159,4.168,4.168,4.174,4.181,4.183,4.190,4.200,4.205,4.214,4.222,4.237,4.249,4.267,4.277,4.285,4.296,4.314,4.331,4.340,4.349,4.361,4.365,4.383,4.392,4.403,4.421,4.430,4.448,4.463,4.482,4.500,3.188,3.256,3.146,3.098,3.081,3.074,3.073,3.066,3.090,3.134,3.254,3.321,4.779,4.794,4.830,4.856,3.133,2.959,2.924,2.891,2.875,2.847,2.831,2.807,2.785,2.762,2.740,2.718,2.713,2.700,5.328,5.365,5.401,5.337,4.898,2.538,2.497,2.491,2.482,2.486,2.479,2.483,2.489},Reflectance=[181]{46.000,64.000,62.000,53.000,48.000,47.000,49.000,44.000,27.000,29.000,50.000,60.000,53.000,46.000,46.000,47.000,46.000,49.000,48.000,46.000,48.000,46.000,46.000,46.000,49.000,46.000,44.000,44.000,46.000,40.000,37.000,31.000,31.000,37.000,48.000,50.000,49.000,45.000,48.000,45.000,40.000,34.000,46.000,55.000,54.000,48.000,48.000,50.000,51.000,49.000,52.000,50.000,55.000,58.000,58.000,49.000,47.000,43.000,50.000,49.000,42.000,48.000,54.000,61.000,56.000,53.000,48.000,49.000,46.000,46.000,47.000,47.000,50.000,48.000,45.000,54.000,63.000,64.000,68.000,69.000,73.000,74.000,76.000,75.000,73.000,72.000,70.000,66.000,66.000,68.000,71.000,75.000,77.000,75.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,25.000,107.000,81.000,76.000,76.000,77.000,77.000,75.000,74.000,74.000,96.000,116.000,77.000,77.000,77.000,77.000,123.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,76.000,75.000,74.000,72.000,63.000,63.000,66.000,63.000,63.000,77.000,32.000,68.000,76.000,78.000,79.000,79.000,79.000,78.000}
-63.994 LMS_LASER_2D_LEFT LMS1 ID=4205,time=1225719875.649107,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=202,Range=[181]{1.025,1.025,1.017,1.021,1.052,1.058,1.072,1.084,1.083,1.105,1.109,1.080,1.100,1.135,1.148,1.167,1.173,1.188,1.197,1.214,1.222,1.235,1.251,1.271,1.280,1.293,1.316,1.339,1.350,1.364,1.392,1.415,1.433,1.461,1.474,1.480,1.514,1.550,1.572,1.591,1.626,1.659,1.674,1.700,1.717,1.748,1.791,1.831,1.865,1.912,1.947,1.983,2.011,2.055,2.103,2.161,2.239,2.295,2.353,2.422,2.504,2.585,2.609,2.612,2.615,2.713,2.758,2.850,2.915,2.985,3.060,3.145,3.214,3.370,3.491,3.582,3.782,3.869,3.905,3.905,3.906,3.953,3.970,3.988,3.989,3.989,3.996,4.004,3.996,4.003,4.039,4.084,4.088,4.085,4.119,4.122,4.125,4.137,4.139,4.139,4.134,4.140,4.139,4.145,4.141,4.152,4.148,4.159,4.158,4.173,4.175,4.181,4.190,4.200,4.199,4.216,4.215,4.232,4.248,4.260,4.266,4.276,4.295,4.305,4.323,4.331,4.349,4.349,4.358,4.377,4.384,4.397,4.413,4.420,4.439,4.458,4.474,4.493,4.509,4.528,3.290,3.181,3.091,3.076,3.068,3.057,3.052,3.060,3.077,3.125,3.257,3.138,3.040,3.122,2.963,2.932,2.913,2.891,2.880,2.858,2.847,2.827,2.817,2.805,2.789,2.792,2.793,5.272,5.306,5.337,5.392,5.401,4.793,4.839,5.428,2.529,2.503,2.499,2.491,2.483,2.484},Reflectance=[181]{48.000,48.000,55.000,54.000,49.000,43.000,46.000,43.000,42.000,35.000,51.000,66.000,58.000,48.000,46.000,42.000,46.000,44.000,46.000,46.000,44.000,47.000,45.000,43.000,48.000,46.000,48.000,45.000,47.000,46.000,45.000,40.000,37.000,42.000,49.000,55.000,51.000,43.000,50.000,50.000,45.000,44.000,48.000,55.000,58.000,57.000,52.000,54.000,53.000,54.000,55.000,55.000,56.000,58.000,59.000,55.000,41.000,43.000,45.000,46.000,42.000,47.000,53.000,51.000,55.000,55.000,59.000,50.000,49.000,46.000,48.000,54.000,53.000,49.000,46.000,50.000,60.000,68.000,69.000,69.000,72.000,73.000,75.000,75.000,73.000,73.000,71.000,68.000,68.000,67.000,70.000,73.000,76.000,75.000,78.000,78.000,79.000,80.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,80.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,112.000,90.000,77.000,77.000,77.000,77.000,75.000,75.000,75.000,77.000,107.000,28.000,36.000,110.000,77.000,78.000,77.000,78.000,79.000,79.000,78.000,77.000,77.000,76.000,74.000,72.000,59.000,68.000,68.000,66.000,62.000,66.000,71.000,74.000,64.000,26.000,67.000,76.000,78.000,79.000,79.000}
-64.018 LMS_LASER_2D_LEFT LMS1 ID=4206,time=1225719875.662447,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=203,Range=[181]{1.025,1.031,1.042,1.040,1.055,1.055,1.069,1.074,1.087,1.094,1.102,1.080,1.089,1.115,1.140,1.157,1.168,1.176,1.194,1.208,1.225,1.232,1.256,1.262,1.277,1.287,1.297,1.330,1.334,1.366,1.384,1.403,1.415,1.442,1.462,1.478,1.497,1.531,1.563,1.592,1.608,1.643,1.666,1.691,1.710,1.733,1.768,1.811,1.855,1.901,1.920,1.965,1.996,2.027,2.077,2.115,2.192,2.268,2.335,2.400,2.469,2.553,2.590,2.604,2.605,2.666,2.740,2.803,2.868,2.969,3.034,3.119,3.192,3.319,3.439,3.526,3.655,3.845,3.906,3.906,3.903,3.930,3.959,3.979,3.992,3.989,3.983,3.994,3.989,3.981,4.025,4.070,4.087,4.086,4.105,4.113,4.122,4.128,4.131,4.131,4.131,4.128,4.122,4.134,4.131,4.140,4.150,4.154,4.161,4.159,4.173,4.173,4.182,4.192,4.199,4.199,4.217,4.224,4.237,4.260,4.259,4.268,4.278,4.294,4.314,4.332,4.341,4.349,4.358,4.367,4.376,4.394,4.403,4.420,4.430,4.446,4.464,4.482,4.501,4.519,4.536,3.151,3.206,3.093,3.074,3.057,3.049,3.031,3.033,3.036,3.051,3.115,3.017,2.976,2.958,2.934,2.918,2.901,2.883,2.881,2.869,2.864,2.860,2.945,2.856,2.851,5.217,5.258,5.288,5.324,5.373,5.394,4.963,4.801,4.957,5.125,5.611,2.548,2.512,2.506,2.483},Reflectance=[181]{43.000,42.000,43.000,42.000,41.000,45.000,44.000,47.000,44.000,48.000,48.000,66.000,64.000,54.000,50.000,45.000,43.000,43.000,48.000,45.000,42.000,46.000,44.000,43.000,46.000,51.000,51.000,46.000,48.000,45.000,46.000,43.000,46.000,49.000,51.000,54.000,55.000,54.000,49.000,45.000,45.000,54.000,52.000,51.000,55.000,54.000,54.000,53.000,52.000,49.000,54.000,55.000,61.000,60.000,60.000,63.000,53.000,42.000,45.000,43.000,47.000,49.000,53.000,51.000,56.000,54.000,55.000,55.000,54.000,46.000,48.000,47.000,51.000,50.000,51.000,46.000,55.000,64.000,69.000,72.000,71.000,73.000,75.000,75.000,74.000,73.000,72.000,70.000,69.000,66.000,69.000,71.000,76.000,76.000,76.000,78.000,79.000,80.000,78.000,79.000,79.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,80.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,77.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,30.000,101.000,77.000,77.000,77.000,77.000,77.000,77.000,75.000,75.000,92.000,77.000,76.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,75.000,74.000,98.000,60.000,43.000,71.000,69.000,68.000,68.000,64.000,67.000,75.000,76.000,76.000,69.000,45.000,42.000,72.000,78.000,79.000}
-64.031 LMS_LASER_2D_LEFT LMS1 ID=4207,time=1225719875.675786,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=204,Range=[181]{1.017,1.028,1.039,1.039,1.051,1.063,1.068,1.067,1.080,1.088,1.098,1.106,1.095,1.098,1.123,1.147,1.175,1.174,1.182,1.202,1.213,1.227,1.242,1.256,1.267,1.276,1.293,1.316,1.342,1.351,1.368,1.391,1.408,1.431,1.452,1.478,1.495,1.512,1.548,1.575,1.604,1.629,1.660,1.683,1.699,1.718,1.760,1.795,1.843,1.876,1.913,1.940,1.999,2.019,2.063,2.115,2.152,2.243,2.305,2.360,2.447,2.521,2.583,2.605,2.603,2.637,2.720,2.768,2.855,2.922,3.002,3.078,3.166,3.272,3.409,3.485,3.627,3.820,3.869,3.907,3.901,3.913,3.949,3.970,3.979,3.982,3.980,3.987,3.990,3.981,4.000,4.047,4.079,4.077,4.089,4.111,4.113,4.122,4.122,4.122,4.131,4.128,4.129,4.131,4.132,4.134,4.140,4.150,4.152,4.161,4.161,4.168,4.181,4.183,4.191,4.200,4.207,4.215,4.223,4.237,4.256,4.258,4.267,4.285,4.304,4.321,4.331,4.340,4.348,4.358,4.376,4.382,4.394,4.412,4.429,4.439,4.456,4.476,4.492,4.512,4.529,4.546,4.570,3.220,3.096,3.075,3.055,3.040,3.025,3.016,3.012,3.009,2.995,2.972,2.960,2.942,2.927,2.916,2.908,2.902,2.903,2.908,2.909,2.916,5.132,5.183,5.210,5.237,5.276,5.312,5.346,5.384,5.392,4.965,4.835,5.428,4.981,4.830,4.813,2.527,2.593},Reflectance=[181]{43.000,40.000,42.000,42.000,39.000,41.000,39.000,48.000,38.000,41.000,45.000,53.000,60.000,57.000,50.000,41.000,38.000,46.000,45.000,43.000,44.000,43.000,45.000,44.000,46.000,46.000,50.000,48.000,43.000,48.000,51.000,49.000,50.000,49.000,54.000,54.000,54.000,54.000,54.000,47.000,43.000,43.000,44.000,47.000,54.000,59.000,54.000,54.000,48.000,50.000,55.000,56.000,55.000,60.000,57.000,61.000,59.000,48.000,49.000,50.000,44.000,45.000,50.000,51.000,55.000,57.000,54.000,55.000,48.000,52.000,50.000,52.000,48.000,48.000,45.000,48.000,50.000,58.000,68.000,74.000,70.000,71.000,74.000,75.000,75.000,74.000,71.000,68.000,69.000,66.000,67.000,70.000,74.000,76.000,74.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,107.000,78.000,77.000,76.000,77.000,77.000,77.000,76.000,75.000,76.000,77.000,78.000,78.000,79.000,78.000,78.000,76.000,74.000,73.000,61.000,39.000,69.000,73.000,73.000,71.000,69.000,69.000,69.000,69.000,66.000,85.000,78.000,65.000,73.000,43.000,34.000,63.000,105.000}
-64.042 LMS_LASER_2D_LEFT LMS1 ID=4208,time=1225719875.689123,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=205,Range=[181]{1.020,1.026,1.033,1.040,1.045,1.056,1.056,1.070,1.072,1.091,1.098,1.094,1.107,1.105,1.124,1.147,1.159,1.161,1.176,1.195,1.201,1.221,1.233,1.240,1.259,1.277,1.295,1.304,1.319,1.337,1.357,1.374,1.397,1.426,1.443,1.457,1.485,1.505,1.530,1.557,1.600,1.618,1.643,1.663,1.688,1.696,1.730,1.788,1.820,1.860,1.895,1.929,1.972,2.015,2.044,2.080,2.135,2.220,2.277,2.312,2.415,2.480,2.562,2.601,2.601,2.603,2.698,2.765,2.841,2.908,2.986,3.043,3.124,3.248,3.363,3.464,3.583,3.725,3.854,3.905,3.902,3.906,3.932,3.962,3.971,3.984,3.978,3.983,3.992,3.973,3.981,4.027,4.063,4.077,4.081,4.107,4.105,4.113,4.122,4.122,4.125,4.128,4.130,4.121,4.122,4.132,4.131,4.141,4.143,4.149,4.155,4.159,4.174,4.178,4.183,4.192,4.199,4.207,4.213,4.235,4.244,4.256,4.266,4.277,4.294,4.313,4.332,4.332,4.341,4.356,4.366,4.372,4.383,4.400,4.420,4.430,4.449,4.464,4.493,4.502,4.518,4.537,4.557,4.575,3.234,3.119,3.073,3.055,3.033,3.018,3.007,2.995,2.985,2.978,2.957,2.949,2.938,2.930,2.924,2.926,2.928,2.949,5.063,5.086,5.130,5.163,5.188,5.226,5.262,5.290,5.333,5.368,5.387,4.974,4.807,4.933,4.899,4.846,4.874,4.827,2.547},Reflectance=[181]{37.000,37.000,43.000,42.000,40.000,45.000,42.000,44.000,46.000,47.000,45.000,48.000,46.000,53.000,50.000,35.000,42.000,48.000,47.000,44.000,47.000,44.000,46.000,50.000,50.000,46.000,45.000,47.000,46.000,50.000,50.000,50.000,49.000,41.000,46.000,52.000,53.000,54.000,54.000,47.000,40.000,47.000,46.000,51.000,54.000,64.000,61.000,55.000,53.000,51.000,55.000,54.000,54.000,54.000,60.000,61.000,55.000,46.000,55.000,55.000,46.000,48.000,49.000,50.000,54.000,55.000,49.000,54.000,57.000,56.000,47.000,55.000,57.000,49.000,46.000,45.000,45.000,50.000,61.000,71.000,73.000,72.000,74.000,75.000,75.000,74.000,72.000,69.000,69.000,65.000,64.000,69.000,72.000,76.000,74.000,77.000,79.000,79.000,78.000,79.000,79.000,80.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,78.000,77.000,79.000,79.000,78.000,78.000,77.000,76.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,110.000,81.000,77.000,76.000,77.000,77.000,77.000,76.000,76.000,78.000,77.000,78.000,77.000,77.000,75.000,73.000,72.000,60.000,74.000,73.000,71.000,73.000,72.000,73.000,71.000,68.000,70.000,67.000,67.000,82.000,78.000,77.000,75.000,80.000,82.000,61.000,28.000}
-64.055 LMS_LASER_2D_LEFT LMS1 ID=4209,time=1225719875.702460,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=206,Range=[181]{1.012,1.014,1.022,1.027,1.041,1.051,1.056,1.064,1.072,1.078,1.090,1.093,1.112,1.123,1.112,1.151,1.148,1.163,1.171,1.181,1.199,1.219,1.223,1.235,1.253,1.268,1.285,1.299,1.321,1.329,1.352,1.372,1.383,1.407,1.431,1.443,1.464,1.489,1.512,1.542,1.582,1.601,1.631,1.660,1.671,1.700,1.724,1.767,1.813,1.853,1.871,1.907,1.955,1.999,2.025,2.067,2.137,2.189,2.253,2.292,2.379,2.450,2.533,2.590,2.592,2.593,2.648,2.746,2.817,2.858,2.971,3.022,3.099,3.217,3.346,3.461,3.566,3.692,3.836,3.904,3.897,3.893,3.910,3.946,3.968,3.975,3.974,3.970,3.982,3.982,3.981,4.001,4.041,4.076,4.068,4.092,4.103,4.113,4.119,4.123,4.127,4.122,4.118,4.121,4.123,4.122,4.132,4.132,4.145,4.143,4.152,4.152,4.168,4.180,4.182,4.183,4.189,4.196,4.213,4.221,4.238,4.252,4.260,4.277,4.283,4.304,4.321,4.332,4.331,4.341,4.356,4.370,4.382,4.394,4.411,4.420,4.439,4.455,4.473,4.493,4.501,4.520,4.546,4.564,4.582,3.263,3.174,3.071,3.047,3.031,3.006,2.992,2.978,2.970,2.969,2.961,2.952,2.946,2.947,2.942,2.954,2.991,5.048,5.073,5.112,5.149,5.169,5.210,5.240,5.274,5.307,5.347,5.391,4.878,4.740,4.711,4.937,4.787,4.814,4.809,4.792},Reflectance=[181]{46.000,42.000,42.000,44.000,43.000,40.000,42.000,45.000,46.000,44.000,45.000,43.000,44.000,41.000,31.000,38.000,41.000,44.000,44.000,49.000,45.000,43.000,49.000,47.000,47.000,46.000,46.000,44.000,45.000,46.000,48.000,53.000,54.000,49.000,49.000,54.000,55.000,55.000,54.000,56.000,46.000,34.000,44.000,50.000,54.000,55.000,54.000,57.000,54.000,51.000,56.000,56.000,54.000,58.000,59.000,59.000,56.000,48.000,48.000,57.000,45.000,42.000,48.000,53.000,50.000,54.000,54.000,50.000,58.000,61.000,51.000,50.000,50.000,51.000,46.000,49.000,47.000,47.000,57.000,63.000,74.000,72.000,73.000,75.000,75.000,74.000,74.000,70.000,69.000,67.000,64.000,67.000,71.000,75.000,76.000,75.000,78.000,78.000,80.000,79.000,79.000,79.000,77.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,112.000,95.000,76.000,76.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,77.000,77.000,76.000,74.000,56.000,74.000,74.000,71.000,71.000,72.000,73.000,72.000,69.000,68.000,66.000,69.000,76.000,75.000,72.000,78.000,70.000,70.000,69.000,61.000}
-64.066 LMS_LASER_2D_LEFT LMS1 ID=4210,time=1225719875.715794,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=207,Range=[181]{1.015,1.012,1.030,1.029,1.041,1.039,1.047,1.065,1.070,1.073,1.081,1.089,1.101,1.109,1.125,1.140,1.144,1.159,1.173,1.181,1.196,1.209,1.226,1.241,1.250,1.262,1.277,1.297,1.316,1.328,1.346,1.371,1.379,1.400,1.417,1.433,1.461,1.477,1.503,1.537,1.575,1.605,1.620,1.648,1.661,1.699,1.729,1.761,1.795,1.835,1.868,1.889,1.937,1.981,2.010,2.049,2.118,2.173,2.225,2.276,2.329,2.434,2.509,2.565,2.596,2.588,2.617,2.724,2.804,2.850,2.949,2.998,3.068,3.169,3.309,3.428,3.537,3.690,3.805,3.879,3.892,3.887,3.897,3.933,3.962,3.970,3.972,3.967,3.971,3.982,3.966,3.986,4.037,4.069,4.070,4.072,4.097,4.103,4.111,4.113,4.114,4.116,4.113,4.113,4.122,4.122,4.125,4.132,4.131,4.143,4.152,4.154,4.167,4.175,4.183,4.183,4.189,4.198,4.206,4.214,4.223,4.246,4.258,4.267,4.285,4.293,4.313,4.323,4.332,4.340,4.346,4.364,4.375,4.391,4.398,4.418,4.436,4.447,4.466,4.480,4.501,4.521,4.537,4.556,4.575,4.598,3.304,3.181,3.064,3.047,3.017,3.003,2.979,2.972,2.964,2.958,2.952,2.951,2.948,2.950,2.957,3.095,5.024,5.057,5.086,5.129,5.157,5.190,5.232,5.265,5.293,5.331,5.369,4.955,4.732,4.677,4.854,4.730,4.856,4.853,4.795},Reflectance=[181]{38.000,38.000,45.000,38.000,43.000,46.000,45.000,42.000,44.000,45.000,46.000,46.000,43.000,47.000,47.000,41.000,43.000,42.000,45.000,46.000,49.000,47.000,47.000,45.000,46.000,48.000,45.000,43.000,36.000,33.000,33.000,44.000,48.000,50.000,54.000,53.000,54.000,53.000,53.000,53.000,42.000,36.000,43.000,52.000,54.000,54.000,49.000,55.000,54.000,48.000,54.000,59.000,58.000,54.000,59.000,58.000,55.000,52.000,48.000,54.000,55.000,47.000,44.000,50.000,52.000,56.000,56.000,48.000,49.000,62.000,49.000,52.000,48.000,57.000,49.000,51.000,50.000,46.000,58.000,57.000,72.000,69.000,71.000,74.000,75.000,75.000,73.000,72.000,68.000,69.000,67.000,68.000,70.000,73.000,76.000,74.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,116.000,102.000,76.000,76.000,77.000,79.000,79.000,79.000,79.000,80.000,79.000,78.000,77.000,78.000,77.000,108.000,72.000,75.000,71.000,68.000,71.000,73.000,72.000,69.000,67.000,67.000,67.000,76.000,71.000,68.000,78.000,68.000,74.000,69.000,58.000}
-64.079 LMS_LASER_2D_LEFT LMS1 ID=4211,time=1225719875.729128,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=208,Range=[181]{1.000,1.022,1.022,1.026,1.032,1.047,1.052,1.056,1.065,1.073,1.078,1.088,1.104,1.110,1.126,1.134,1.149,1.155,1.165,1.182,1.183,1.208,1.225,1.228,1.244,1.261,1.277,1.293,1.311,1.327,1.333,1.331,1.378,1.392,1.409,1.424,1.451,1.479,1.494,1.520,1.557,1.597,1.618,1.642,1.653,1.679,1.716,1.756,1.786,1.829,1.863,1.877,1.920,1.964,2.010,2.043,2.091,2.152,2.220,2.273,2.317,2.398,2.477,2.554,2.592,2.588,2.605,2.708,2.781,2.864,2.906,2.975,3.042,3.133,3.242,3.396,3.498,3.648,3.796,3.850,3.887,3.883,3.890,3.925,3.947,3.963,3.970,3.962,3.963,3.984,3.968,3.980,4.017,4.063,4.069,4.064,4.095,4.101,4.103,4.112,4.112,4.114,4.110,4.113,4.114,4.116,4.127,4.125,4.131,4.132,4.145,4.141,4.158,4.167,4.175,4.176,4.183,4.190,4.196,4.205,4.215,4.229,4.251,4.267,4.275,4.285,4.305,4.312,4.324,4.330,4.337,4.359,4.368,4.377,4.397,4.406,4.424,4.445,4.458,4.474,4.493,4.511,4.529,4.545,4.564,4.591,4.618,3.125,3.189,3.061,3.038,3.006,2.993,2.978,2.970,2.961,2.952,2.949,2.948,2.949,2.955,3.053,3.011,5.048,5.079,5.117,5.140,5.180,5.218,5.253,5.278,5.316,5.358,5.392,4.792,4.715,4.902,4.672,4.741,5.016,4.830},Reflectance=[181]{44.000,42.000,42.000,44.000,36.000,41.000,44.000,45.000,42.000,46.000,44.000,40.000,40.000,43.000,43.000,38.000,42.000,46.000,45.000,45.000,47.000,45.000,45.000,48.000,47.000,47.000,45.000,46.000,40.000,37.000,33.000,30.000,48.000,54.000,54.000,53.000,53.000,54.000,53.000,53.000,47.000,39.000,40.000,49.000,54.000,53.000,54.000,52.000,50.000,46.000,52.000,54.000,54.000,55.000,56.000,60.000,58.000,55.000,40.000,46.000,50.000,45.000,45.000,49.000,50.000,52.000,56.000,49.000,50.000,56.000,52.000,49.000,48.000,57.000,54.000,49.000,50.000,48.000,58.000,59.000,65.000,70.000,69.000,74.000,76.000,76.000,73.000,68.000,68.000,67.000,67.000,68.000,69.000,74.000,76.000,75.000,76.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,76.000,76.000,76.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,32.000,102.000,75.000,76.000,77.000,78.000,79.000,79.000,79.000,79.000,78.000,77.000,78.000,77.000,94.000,29.000,74.000,74.000,67.000,71.000,72.000,73.000,71.000,67.000,68.000,67.000,64.000,78.000,71.000,78.000,73.000,78.000,75.000,58.000}
-64.090 LMS_LASER_2D_LEFT LMS1 ID=4212,time=1225719875.742460,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=209,Range=[181]{0.997,1.015,1.023,1.026,1.029,1.041,1.043,1.056,1.067,1.072,1.084,1.088,1.096,1.107,1.119,1.130,1.148,1.151,1.160,1.169,1.191,1.202,1.219,1.225,1.242,1.258,1.270,1.285,1.303,1.320,1.336,1.331,1.378,1.384,1.400,1.425,1.442,1.469,1.499,1.529,1.556,1.583,1.605,1.634,1.659,1.679,1.708,1.733,1.779,1.831,1.854,1.885,1.922,1.963,2.007,2.048,2.085,2.137,2.206,2.271,2.327,2.384,2.457,2.534,2.581,2.590,2.593,2.679,2.765,2.837,2.898,2.956,3.016,3.104,3.233,3.378,3.467,3.599,3.771,3.821,3.904,3.888,3.883,3.912,3.945,3.962,3.966,3.961,3.959,3.977,3.969,3.971,4.011,4.045,4.067,4.061,4.085,4.101,4.109,4.112,4.113,4.104,4.105,4.114,4.113,4.113,4.113,4.125,4.122,4.134,4.140,4.140,4.149,4.165,4.184,4.175,4.181,4.189,4.188,4.205,4.216,4.231,4.240,4.258,4.269,4.284,4.294,4.306,4.312,4.331,4.337,4.348,4.367,4.376,4.386,4.404,4.421,4.435,4.453,4.462,4.481,4.501,4.521,4.537,4.564,4.584,4.610,4.628,3.287,3.170,3.058,3.027,2.997,2.976,2.968,2.960,2.951,2.944,2.947,2.946,2.954,3.006,3.031,5.037,5.066,5.099,5.128,5.170,5.208,5.244,5.273,5.306,5.346,5.383,4.761,4.736,4.877,4.656,4.694,5.058,5.154},Reflectance=[181]{47.000,42.000,38.000,44.000,41.000,36.000,40.000,42.000,43.000,45.000,43.000,41.000,46.000,45.000,43.000,40.000,41.000,47.000,43.000,48.000,45.000,43.000,43.000,45.000,45.000,49.000,47.000,46.000,46.000,46.000,35.000,29.000,43.000,54.000,53.000,54.000,53.000,54.000,52.000,53.000,50.000,45.000,43.000,45.000,53.000,53.000,54.000,54.000,55.000,45.000,48.000,54.000,55.000,54.000,55.000,54.000,59.000,56.000,48.000,44.000,45.000,48.000,46.000,56.000,53.000,53.000,54.000,48.000,50.000,52.000,56.000,48.000,48.000,52.000,54.000,52.000,48.000,49.000,59.000,58.000,61.000,71.000,70.000,73.000,75.000,75.000,74.000,68.000,67.000,67.000,68.000,68.000,70.000,72.000,75.000,76.000,75.000,78.000,77.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,76.000,76.000,76.000,76.000,76.000,77.000,77.000,77.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,116.000,92.000,75.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,82.000,50.000,74.000,75.000,69.000,70.000,72.000,73.000,71.000,69.000,68.000,69.000,65.000,74.000,74.000,75.000,71.000,70.000,39.000,68.000}
-64.102 LMS_LASER_2D_LEFT LMS1 ID=4213,time=1225719875.755791,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=210,Range=[181]{1.003,1.007,1.012,1.024,1.030,1.038,1.043,1.050,1.056,1.067,1.079,1.097,1.097,1.108,1.119,1.126,1.135,1.150,1.157,1.161,1.189,1.204,1.215,1.222,1.234,1.249,1.266,1.277,1.303,1.315,1.342,1.322,1.344,1.395,1.409,1.430,1.451,1.461,1.497,1.520,1.554,1.575,1.606,1.618,1.654,1.684,1.706,1.741,1.760,1.811,1.852,1.885,1.913,1.955,2.005,2.043,2.092,2.135,2.186,2.263,2.325,2.387,2.446,2.522,2.557,2.583,2.597,2.660,2.749,2.815,2.897,2.944,2.997,3.081,3.238,3.363,3.467,3.596,3.752,3.803,3.904,3.885,3.879,3.913,3.943,3.954,3.967,3.954,3.953,3.987,3.970,3.964,3.996,4.043,4.063,4.060,4.081,4.091,4.104,4.105,4.116,4.105,4.103,4.105,4.105,4.111,4.113,4.122,4.125,4.134,4.132,4.143,4.150,4.166,4.175,4.175,4.175,4.182,4.189,4.196,4.206,4.224,4.240,4.248,4.267,4.277,4.283,4.294,4.306,4.321,4.329,4.342,4.360,4.377,4.389,4.398,4.415,4.432,4.442,4.460,4.481,4.493,4.519,4.537,4.554,4.582,4.600,4.626,4.643,3.234,3.095,3.057,3.019,2.999,2.966,2.961,2.944,2.949,2.947,2.950,2.958,2.980,3.129,5.032,5.066,5.087,5.125,5.159,5.203,5.236,5.273,5.307,5.338,5.368,4.728,4.718,4.757,4.664,4.682,4.878,5.123},Reflectance=[181]{40.000,43.000,38.000,43.000,46.000,45.000,39.000,43.000,45.000,43.000,40.000,41.000,46.000,42.000,43.000,43.000,43.000,47.000,46.000,48.000,41.000,44.000,40.000,44.000,47.000,49.000,46.000,46.000,46.000,48.000,38.000,29.000,28.000,43.000,54.000,52.000,53.000,54.000,51.000,53.000,53.000,51.000,46.000,47.000,51.000,52.000,53.000,54.000,54.000,49.000,51.000,50.000,55.000,54.000,54.000,52.000,59.000,58.000,50.000,44.000,37.000,41.000,48.000,55.000,54.000,50.000,56.000,51.000,52.000,53.000,55.000,50.000,52.000,50.000,49.000,50.000,48.000,52.000,58.000,64.000,57.000,70.000,69.000,74.000,75.000,75.000,74.000,68.000,68.000,70.000,68.000,69.000,71.000,71.000,74.000,76.000,74.000,77.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,110.000,75.000,74.000,75.000,77.000,78.000,78.000,79.000,79.000,77.000,78.000,78.000,77.000,117.000,72.000,75.000,71.000,72.000,72.000,72.000,71.000,69.000,68.000,69.000,67.000,72.000,74.000,75.000,71.000,69.000,49.000,65.000}
-64.102 LMS_LASER_2D_RIGHT LMS2 ID=4085,time=1225719875.747981,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=174,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,18.374,15.539,12.802,10.719,9.811,8.931,8.144,7.360,6.837,6.262,5.831,5.477,5.147,4.828,4.484,4.339,4.066,3.882,3.658,3.447,3.248,3.172,3.037,2.934,2.827,2.724,2.613,2.551,2.460,2.382,2.300,2.141,2.083,2.047,1.994,1.937,1.902,1.850,1.815,1.770,1.723,1.688,1.658,1.604,1.565,1.528,1.506,1.478,1.438,1.422,1.389,1.377,1.352,1.312,1.291,1.279,1.258,1.243,1.217,1.200,1.192,1.167,1.158,1.157,1.171,1.181,1.183,1.189,1.180,1.175,1.182,1.184,1.177,1.163,1.159,1.137,1.125,1.128,1.081,1.075,1.083,1.041,1.032,1.019,1.019,1.024,1.027},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,118.000,112.000,92.000,63.000,56.000,56.000,55.000,63.000,66.000,67.000,69.000,69.000,71.000,74.000,76.000,74.000,76.000,78.000,76.000,79.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,81.000,80.000,83.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,77.000,77.000,78.000,77.000,69.000,72.000,74.000,76.000,77.000,76.000,74.000,72.000,67.000,71.000,72.000,72.000,71.000,72.000,71.000,71.000,59.000,52.000,46.000,39.000,31.000,31.000,32.000,41.000,50.000,45.000,36.000,55.000,57.000,37.000,27.000,28.000,34.000,28.000,33.000,37.000,39.000,43.000,44.000}
-64.114 LMS_LASER_2D_RIGHT LMS2 ID=4086,time=1225719875.761318,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=175,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.581,-1.000,15.841,12.969,10.999,9.883,9.004,8.188,7.395,6.872,6.341,5.878,5.519,5.191,4.863,4.481,4.353,4.085,3.880,3.699,3.460,3.259,3.181,3.071,2.937,2.838,2.740,2.626,2.561,2.469,2.389,2.286,2.200,2.101,2.047,1.994,1.936,1.893,1.852,1.812,1.770,1.732,1.690,1.665,1.612,1.566,1.532,1.505,1.488,1.449,1.423,1.387,1.362,1.352,1.321,1.292,1.280,1.259,1.235,1.217,1.209,1.192,1.175,1.167,1.157,1.164,1.173,1.184,1.190,1.186,1.189,1.194,1.183,1.174,1.172,1.160,1.135,1.126,1.119,1.117,1.068,1.055,1.046,1.023,1.022,1.021,1.023,1.023},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,0.000,111.000,116.000,87.000,66.000,57.000,56.000,55.000,63.000,66.000,67.000,68.000,69.000,71.000,75.000,80.000,75.000,75.000,77.000,75.000,77.000,80.000,80.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,81.000,82.000,82.000,81.000,80.000,80.000,80.000,78.000,79.000,80.000,79.000,80.000,80.000,78.000,77.000,78.000,78.000,75.000,74.000,74.000,74.000,74.000,77.000,75.000,75.000,73.000,69.000,71.000,72.000,72.000,72.000,72.000,72.000,69.000,67.000,56.000,46.000,37.000,34.000,35.000,43.000,46.000,49.000,45.000,47.000,54.000,58.000,55.000,41.000,26.000,27.000,28.000,30.000,36.000,42.000,42.000,42.000}
-64.123 DESIRED_THRUST iJoystick 85.5708487197
-64.123 DESIRED_RUDDER iJoystick 0
-64.123 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.1636,20.1684,-0.9560},Vel=[3x1]{-0.8493,-0.5997,0.1282},Raw=[2x1]{22.5331,-0.9560},time=1225719875.77051615715027,Speed=1.03968926141176,Pitch=0.03589365974142,Roll=0.00448670746768,PitchDot=-0.00000000000000,RollDot=-0.00105437625490
-64.123 ODOMETRY_POSE iPlatform Pose=[3x1]{6.1636,20.1684,-0.9562},Vel=[3x1]{-0.8493,-0.5997,0.1282},Raw=[2x1]{22.5331,-0.9560},time=1225719875.7705,Speed=1.0397,Pitch=0.0170,Roll=0.0319,PitchDot=-0.0001,RollDot=-0.0010
-64.123 VEHICLE_GEOMETRY iPlatform Name=LISA, Sensor_0=LMS_LASER_2D, Pose3D_0=[4x1]{0.0000,0.3500,0.0000,0.0000},SHAPE_2D=[2x8]{0.3300,0.3300,0.2100,0.2100,-0.2100,-0.2100,-0.3300,-0.3300,-0.4100,0.4100,0.4100,0.5700,0.5700,0.4100,0.4100,-0.4100,}
-64.126 LMS_LASER_2D_LEFT LMS1 ID=4214,time=1225719875.769132,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=211,Range=[181]{1.009,1.007,1.019,1.024,1.033,1.039,1.047,1.055,1.055,1.064,1.080,1.085,1.087,1.105,1.118,1.127,1.140,1.149,1.162,1.164,1.182,1.196,1.220,1.217,1.233,1.251,1.268,1.275,1.296,1.316,1.338,1.350,1.340,1.363,1.405,1.419,1.446,1.470,1.490,1.517,1.546,1.568,1.597,1.626,1.655,1.675,1.712,1.734,1.769,1.812,1.847,1.877,1.918,1.946,1.981,2.041,2.078,2.127,2.189,2.258,2.316,2.374,2.442,2.519,2.566,2.585,2.596,2.657,2.732,2.815,2.889,2.947,2.996,3.060,3.236,3.354,3.465,3.579,3.750,3.785,3.906,3.883,3.880,3.902,3.933,3.956,3.961,3.957,3.954,3.974,3.968,3.963,3.993,4.043,4.063,4.059,4.081,4.093,4.096,4.104,4.114,4.104,4.105,4.104,4.105,4.111,4.112,4.122,4.122,4.122,4.134,4.143,4.141,4.156,4.176,4.183,4.174,4.182,4.190,4.196,4.205,4.215,4.229,4.246,4.258,4.275,4.283,4.293,4.294,4.321,4.337,4.342,4.353,4.363,4.381,4.400,4.416,4.433,4.443,4.460,4.482,4.491,4.511,4.537,4.553,4.573,4.601,4.624,4.635,3.340,3.198,3.112,3.066,3.067,3.033,2.967,2.952,2.944,2.943,2.944,2.949,2.965,3.075,3.009,5.056,5.089,5.120,5.153,5.200,5.228,5.257,5.297,5.337,5.302,4.739,4.707,4.709,4.690,4.697,4.735,4.975},Reflectance=[181]{37.000,43.000,40.000,38.000,43.000,45.000,45.000,45.000,46.000,45.000,45.000,40.000,44.000,46.000,43.000,40.000,46.000,45.000,44.000,46.000,45.000,44.000,39.000,47.000,46.000,45.000,46.000,49.000,51.000,48.000,41.000,33.000,28.000,29.000,49.000,51.000,51.000,54.000,52.000,52.000,53.000,48.000,46.000,45.000,47.000,48.000,48.000,55.000,54.000,53.000,53.000,50.000,53.000,54.000,54.000,55.000,56.000,59.000,55.000,45.000,44.000,40.000,45.000,49.000,50.000,51.000,56.000,54.000,56.000,53.000,52.000,52.000,55.000,55.000,48.000,54.000,47.000,49.000,58.000,67.000,54.000,67.000,69.000,73.000,74.000,76.000,75.000,69.000,68.000,69.000,67.000,68.000,70.000,71.000,74.000,76.000,74.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,117.000,102.000,80.000,75.000,86.000,86.000,78.000,79.000,79.000,78.000,78.000,78.000,77.000,99.000,25.000,74.000,71.000,73.000,72.000,71.000,71.000,69.000,68.000,69.000,69.000,75.000,73.000,71.000,69.000,71.000,58.000,66.000}
-64.139 LMS_LASER_2D_LEFT LMS1 ID=4215,time=1225719875.782473,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=212,Range=[181]{1.001,1.017,1.017,1.026,1.033,1.035,1.048,1.047,1.056,1.073,1.081,1.090,1.098,1.105,1.116,1.133,1.135,1.140,1.159,1.165,1.182,1.192,1.212,1.225,1.230,1.252,1.262,1.275,1.294,1.313,1.332,1.357,1.342,1.368,1.417,1.425,1.453,1.470,1.485,1.512,1.547,1.574,1.597,1.621,1.656,1.680,1.709,1.744,1.768,1.807,1.847,1.873,1.917,1.945,1.991,2.045,2.085,2.131,2.190,2.259,2.309,2.377,2.442,2.521,2.576,2.577,2.585,2.654,2.733,2.803,2.893,2.951,3.002,3.078,3.232,3.356,3.463,3.587,3.739,3.793,3.905,3.879,3.875,3.900,3.936,3.955,3.958,3.959,3.953,3.972,3.970,3.964,3.996,4.032,4.063,4.058,4.072,4.091,4.094,4.103,4.102,4.105,4.104,4.104,4.111,4.113,4.113,4.114,4.123,4.122,4.131,4.145,4.141,4.156,4.167,4.175,4.175,4.183,4.191,4.199,4.208,4.224,4.233,4.238,4.248,4.265,4.283,4.293,4.293,4.320,4.327,4.336,4.355,4.365,4.382,4.389,4.407,4.424,4.443,4.462,4.473,4.492,4.510,4.530,4.546,4.565,4.590,4.611,4.627,4.652,3.265,3.200,3.174,3.171,3.105,3.030,2.960,2.952,2.945,2.947,2.950,2.960,3.018,3.012,5.056,5.084,5.120,5.150,5.189,5.226,5.255,5.297,5.337,5.186,4.759,4.708,4.696,4.733,4.776,4.760,4.940},Reflectance=[181]{36.000,40.000,39.000,39.000,38.000,44.000,42.000,46.000,45.000,42.000,41.000,45.000,45.000,46.000,42.000,42.000,48.000,46.000,42.000,46.000,45.000,42.000,44.000,46.000,49.000,47.000,48.000,50.000,50.000,47.000,47.000,35.000,28.000,28.000,45.000,50.000,54.000,54.000,53.000,50.000,46.000,46.000,49.000,48.000,48.000,46.000,47.000,51.000,54.000,51.000,53.000,52.000,53.000,54.000,55.000,53.000,56.000,56.000,52.000,47.000,45.000,41.000,45.000,45.000,47.000,51.000,55.000,57.000,56.000,55.000,50.000,50.000,50.000,49.000,50.000,55.000,46.000,48.000,60.000,68.000,54.000,66.000,67.000,72.000,75.000,76.000,74.000,70.000,68.000,69.000,68.000,69.000,71.000,71.000,74.000,75.000,74.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,78.000,78.000,114.000,104.000,91.000,108.000,111.000,91.000,78.000,78.000,79.000,79.000,78.000,76.000,84.000,45.000,74.000,72.000,73.000,71.000,70.000,71.000,69.000,68.000,69.000,72.000,78.000,71.000,70.000,76.000,76.000,72.000,71.000}
-64.142 LMS1_STATUS LMS1 AppErrorFlag=false,Uptime=-1617.63,MOOSName=LMS1,Publishing=LMS1_STATUS,LMS_LASER_2D_LEFT,MOOS_DEBUG,Subscribing=LASER_LAG,LMS1_CMD,LOCAL_LASER_LAG,
-64.147 DESIRED_THRUST iJoystick 85.5708487197
-64.147 DESIRED_RUDDER iJoystick 0
-64.126 LMS_LASER_2D_RIGHT LMS2 ID=4087,time=1225719875.774654,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=176,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.105,13.070,10.992,10.019,9.086,8.265,7.515,6.960,6.391,5.928,5.553,5.219,4.926,4.493,4.353,4.134,3.886,3.737,3.508,3.306,3.199,3.068,2.963,2.855,2.741,2.644,2.571,2.478,2.399,2.263,2.214,2.124,2.063,2.003,1.955,1.892,1.855,1.822,1.777,1.732,1.698,1.656,1.613,1.565,1.540,1.519,1.477,1.449,1.414,1.390,1.377,1.354,1.323,1.300,1.279,1.260,1.242,1.235,1.217,1.193,1.183,1.175,1.173,1.171,1.171,1.184,1.190,1.182,1.177,1.190,1.182,1.185,1.158,1.142,1.130,1.130,1.117,1.110,1.108,1.064,1.078,1.053,1.019,1.012,1.011,1.020},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,106.000,119.000,93.000,66.000,59.000,56.000,54.000,61.000,65.000,67.000,68.000,69.000,69.000,74.000,78.000,76.000,74.000,78.000,76.000,75.000,78.000,79.000,79.000,80.000,80.000,81.000,81.000,81.000,81.000,82.000,82.000,81.000,81.000,80.000,81.000,80.000,79.000,80.000,80.000,79.000,79.000,80.000,78.000,77.000,78.000,79.000,77.000,73.000,73.000,75.000,76.000,77.000,76.000,75.000,71.000,70.000,70.000,72.000,72.000,73.000,71.000,72.000,68.000,64.000,60.000,47.000,40.000,33.000,31.000,40.000,33.000,47.000,57.000,58.000,56.000,56.000,54.000,54.000,43.000,29.000,35.000,37.000,35.000,37.000,37.000,35.000}
-64.139 LMS_LASER_2D_RIGHT LMS2 ID=4088,time=1225719875.787989,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=177,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.200,13.142,11.331,10.081,9.096,8.249,7.498,6.950,6.400,5.946,5.561,5.219,4.936,4.563,4.364,4.155,3.896,3.733,3.533,3.321,3.196,3.068,2.958,2.856,2.750,2.654,2.569,2.476,2.400,2.262,2.225,2.132,2.058,2.003,1.971,1.910,1.863,1.822,1.776,1.732,1.704,1.662,1.613,1.575,1.542,1.516,1.489,1.457,1.414,1.398,1.381,1.351,1.328,1.300,1.285,1.259,1.242,1.225,1.209,1.208,1.183,1.175,1.173,1.178,1.175,1.181,1.187,1.184,1.160,1.163,1.166,1.168,1.168,1.144,1.133,1.125,1.123,1.106,1.105,1.079,1.065,1.053,1.020,1.018,1.014,1.010},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,103.000,121.000,83.000,68.000,60.000,57.000,54.000,61.000,65.000,67.000,68.000,69.000,70.000,73.000,75.000,75.000,75.000,77.000,77.000,77.000,77.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,81.000,82.000,80.000,78.000,79.000,80.000,81.000,80.000,79.000,80.000,79.000,79.000,78.000,79.000,78.000,77.000,78.000,78.000,75.000,73.000,74.000,77.000,77.000,77.000,75.000,75.000,67.000,69.000,69.000,70.000,71.000,70.000,72.000,72.000,69.000,63.000,57.000,48.000,34.000,32.000,29.000,30.000,31.000,31.000,47.000,58.000,61.000,57.000,52.000,52.000,48.000,31.000,31.000,32.000,34.000,37.000,38.000,35.000}
-64.150 LMS_LASER_2D_RIGHT LMS2 ID=4089,time=1225719875.801323,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=178,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,21.723,16.299,13.132,11.292,10.029,9.146,8.292,7.553,6.985,6.391,5.937,5.578,5.229,4.954,4.606,4.375,4.155,3.921,3.714,3.529,3.340,3.219,3.080,2.974,2.865,2.760,2.661,2.568,2.460,2.399,2.293,2.247,2.165,2.084,2.019,1.962,1.910,1.856,1.821,1.767,1.732,1.698,1.661,1.613,1.578,1.542,1.517,1.483,1.449,1.422,1.396,1.370,1.351,1.326,1.306,1.295,1.269,1.258,1.223,1.199,1.184,1.174,1.176,1.166,1.170,1.176,1.182,1.182,1.173,1.169,1.157,1.169,1.169,1.159,1.139,1.136,1.139,1.127,1.118,1.107,1.086,1.049,1.021,1.027,1.011,1.009,1.014},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,99.000,120.000,84.000,67.000,59.000,57.000,55.000,60.000,64.000,67.000,67.000,69.000,70.000,73.000,72.000,75.000,74.000,76.000,77.000,77.000,78.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,76.000,74.000,73.000,72.000,76.000,74.000,72.000,74.000,73.000,71.000,70.000,67.000,67.000,71.000,74.000,76.000,72.000,70.000,64.000,54.000,49.000,32.000,31.000,29.000,29.000,33.000,47.000,54.000,60.000,58.000,52.000,51.000,47.000,46.000,35.000,28.000,28.000,35.000,37.000,39.000,38.000}
-64.159 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.1970,20.1919,-0.9576},Vel=[3x1]{-0.8503,-0.5983,-6.9231},Raw=[2x1]{22.5740,-0.9576},time=1225719875.80652046203613,Speed=1.03968926141176,Pitch=0.03813701347526,Roll=0.00224335373384,PitchDot=0.02019018360455,RollDot=0.00004486707468
-64.159 ODOMETRY_POSE iPlatform Pose=[3x1]{6.1970,20.1919,-0.9579},Vel=[3x1]{-0.8503,-0.5983,-0.6400},Raw=[2x1]{22.5740,-0.9576},time=1225719875.8065,Speed=1.0397,Pitch=0.0201,Roll=0.0325,PitchDot=0.0162,RollDot=0.0121
-64.171 DESIRED_THRUST iJoystick 85.5708487197
-64.171 DESIRED_RUDDER iJoystick 0
-63.348 CAMERA_FILE_WRITE iCameraLadybug time=1225719874.996,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.996-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.996-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.996-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.996-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719874.996-4.jpg
-64.150 LMS_LASER_2D_LEFT LMS1 ID=4216,time=1225719875.795811,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=213,Range=[181]{0.970,0.973,1.013,1.022,1.026,1.033,1.039,1.046,1.058,1.071,1.072,1.084,1.090,1.102,1.115,1.119,1.137,1.147,1.154,1.174,1.182,1.195,1.207,1.224,1.233,1.245,1.256,1.269,1.291,1.306,1.328,1.357,1.344,1.363,1.416,1.426,1.443,1.468,1.479,1.519,1.547,1.567,1.593,1.618,1.646,1.674,1.708,1.748,1.758,1.809,1.836,1.882,1.913,1.946,1.990,2.023,2.093,2.128,2.181,2.262,2.310,2.379,2.441,2.513,2.577,2.581,2.576,2.635,2.732,2.788,2.881,2.950,3.002,3.081,3.230,3.344,3.461,3.578,3.732,3.791,3.902,3.879,3.880,3.898,3.936,3.955,3.961,3.961,3.953,3.971,3.969,3.958,3.995,4.030,4.059,4.059,4.075,4.096,4.093,4.096,4.104,4.104,4.104,4.107,4.104,4.111,4.113,4.123,4.123,4.134,4.134,4.131,4.143,4.156,4.167,4.175,4.174,4.181,4.190,4.198,4.207,4.214,4.229,4.239,4.247,4.256,4.275,4.286,4.292,4.321,4.326,4.334,4.346,4.363,4.382,4.390,4.406,4.423,4.442,4.452,4.474,4.491,4.512,4.527,4.545,4.564,4.593,4.611,4.626,4.644,3.171,3.289,3.245,3.160,3.032,3.099,3.036,2.959,2.935,2.938,2.943,2.944,2.968,2.990,5.056,5.088,5.122,5.148,5.196,5.225,5.257,5.297,5.338,5.365,4.757,4.712,4.672,4.792,5.383,4.772,4.916},Reflectance=[181]{29.000,29.000,34.000,42.000,44.000,48.000,42.000,46.000,43.000,41.000,46.000,43.000,46.000,48.000,46.000,48.000,44.000,41.000,44.000,45.000,45.000,44.000,46.000,46.000,46.000,48.000,49.000,51.000,49.000,51.000,49.000,37.000,28.000,29.000,41.000,54.000,54.000,53.000,54.000,53.000,50.000,51.000,47.000,47.000,51.000,48.000,46.000,49.000,53.000,52.000,49.000,49.000,55.000,54.000,54.000,54.000,55.000,59.000,52.000,43.000,45.000,42.000,46.000,47.000,51.000,53.000,55.000,56.000,56.000,49.000,52.000,53.000,50.000,50.000,53.000,57.000,49.000,52.000,57.000,68.000,52.000,63.000,69.000,72.000,75.000,76.000,75.000,70.000,68.000,68.000,68.000,67.000,70.000,70.000,73.000,76.000,75.000,76.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,19.000,118.000,113.000,9.000,38.000,112.000,93.000,78.000,79.000,79.000,78.000,76.000,76.000,55.000,74.000,74.000,73.000,71.000,70.000,70.000,69.000,68.000,69.000,66.000,80.000,72.000,69.000,83.000,64.000,70.000,72.000}
-64.162 LMS_LASER_2D_LEFT LMS1 ID=4217,time=1225719875.809149,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=214,Range=[181]{1.002,1.007,1.013,1.021,1.033,1.036,1.047,1.047,1.064,1.069,1.074,1.079,1.088,1.100,1.115,1.114,1.140,1.152,1.157,1.168,1.179,1.195,1.204,1.219,1.233,1.252,1.270,1.277,1.294,1.312,1.325,1.357,1.346,1.366,1.419,1.421,1.445,1.468,1.479,1.514,1.545,1.560,1.592,1.612,1.650,1.674,1.706,1.740,1.759,1.796,1.827,1.883,1.912,1.955,1.999,2.031,2.091,2.133,2.178,2.256,2.310,2.371,2.434,2.506,2.573,2.582,2.576,2.648,2.757,2.793,2.878,2.949,3.002,3.088,3.229,3.344,3.455,3.599,3.732,3.803,3.906,3.887,3.878,3.899,3.934,3.946,3.959,3.957,3.952,3.974,3.970,3.962,3.995,4.025,4.063,4.058,4.072,4.091,4.093,4.103,4.104,4.107,4.107,4.099,4.105,4.113,4.113,4.113,4.125,4.123,4.132,4.134,4.140,4.157,4.166,4.174,4.175,4.175,4.190,4.198,4.198,4.215,4.231,4.240,4.250,4.257,4.275,4.276,4.300,4.321,4.336,4.335,4.344,4.355,4.384,4.391,4.407,4.425,4.432,4.462,4.471,4.492,4.510,4.527,4.548,4.565,4.592,4.612,4.627,4.644,4.662,4.696,3.139,4.754,4.771,3.018,3.088,2.960,2.947,2.940,2.943,2.939,2.960,3.092,5.055,5.090,5.120,5.160,5.196,5.225,5.259,5.294,5.338,5.319,4.798,4.758,4.701,4.984,5.445,4.778,4.864},Reflectance=[181]{40.000,38.000,34.000,38.000,43.000,44.000,45.000,46.000,45.000,44.000,47.000,46.000,46.000,47.000,45.000,50.000,45.000,43.000,46.000,43.000,44.000,48.000,49.000,48.000,45.000,42.000,42.000,46.000,50.000,50.000,48.000,41.000,29.000,30.000,36.000,52.000,47.000,49.000,54.000,55.000,53.000,55.000,54.000,48.000,49.000,48.000,46.000,50.000,54.000,54.000,49.000,49.000,51.000,54.000,55.000,54.000,54.000,57.000,55.000,41.000,51.000,46.000,47.000,48.000,53.000,53.000,55.000,54.000,47.000,55.000,51.000,52.000,54.000,53.000,56.000,57.000,50.000,53.000,61.000,64.000,51.000,61.000,68.000,72.000,75.000,75.000,75.000,69.000,68.000,69.000,68.000,68.000,70.000,71.000,74.000,75.000,74.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,78.000,78.000,29.000,77.000,77.000,37.000,110.000,78.000,79.000,79.000,78.000,77.000,76.000,114.000,74.000,74.000,73.000,72.000,70.000,70.000,70.000,67.000,69.000,66.000,81.000,78.000,67.000,80.000,63.000,69.000,72.000}
-64.162 LMS_LASER_2D_RIGHT LMS2 ID=4090,time=1225719875.814655,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=179,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.174,13.157,11.243,10.047,9.151,8.301,7.535,6.922,6.383,5.936,5.569,5.229,4.935,4.623,4.367,4.143,3.904,3.714,3.527,3.328,3.228,3.103,2.967,2.856,2.747,2.669,2.568,2.461,2.399,2.310,2.246,2.158,2.095,2.019,1.961,1.910,1.855,1.803,1.776,1.735,1.705,1.659,1.613,1.571,1.550,1.521,1.483,1.436,1.404,1.387,1.378,1.351,1.327,1.305,1.302,1.277,1.249,1.232,1.208,1.193,1.176,1.167,1.157,1.159,1.179,1.192,1.183,1.173,1.185,1.179,1.171,1.140,1.146,1.146,1.145,1.144,1.122,1.094,1.091,1.092,1.072,1.058,1.019,1.018,1.011,1.002},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,104.000,119.000,87.000,67.000,58.000,57.000,55.000,61.000,65.000,66.000,68.000,69.000,69.000,73.000,73.000,74.000,74.000,76.000,76.000,76.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,80.000,78.000,78.000,78.000,79.000,78.000,77.000,76.000,75.000,72.000,73.000,72.000,74.000,77.000,72.000,66.000,69.000,67.000,67.000,69.000,73.000,74.000,72.000,70.000,61.000,48.000,42.000,38.000,31.000,32.000,33.000,55.000,71.000,65.000,59.000,51.000,43.000,45.000,59.000,58.000,50.000,32.000,33.000,33.000,39.000,39.000,37.000}
-64.174 LMS_LASER_2D_RIGHT LMS2 ID=4091,time=1225719875.827985,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=180,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.027,22.090,15.839,13.000,11.053,9.866,9.069,8.207,7.461,6.850,6.323,5.911,5.528,5.174,4.890,4.588,4.349,4.100,3.880,3.704,3.502,3.332,3.216,3.084,2.958,2.848,2.724,2.660,2.569,2.459,2.381,2.310,2.218,2.139,2.068,2.007,1.941,1.898,1.847,1.798,1.762,1.733,1.689,1.642,1.604,1.571,1.542,1.516,1.487,1.444,1.405,1.379,1.351,1.333,1.324,1.296,1.286,1.259,1.242,1.226,1.209,1.191,1.182,1.167,1.157,1.155,1.166,1.182,1.181,1.185,1.185,1.190,1.166,1.147,1.150,1.159,1.154,1.135,1.123,1.119,1.096,1.084,1.082,1.058,1.013,1.010,1.013,1.002},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,31.000,6.000,110.000,112.000,84.000,65.000,56.000,57.000,54.000,61.000,65.000,66.000,69.000,69.000,70.000,72.000,74.000,73.000,75.000,76.000,77.000,78.000,80.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,75.000,78.000,80.000,79.000,79.000,78.000,79.000,78.000,78.000,77.000,75.000,74.000,74.000,73.000,73.000,72.000,72.000,68.000,67.000,70.000,72.000,71.000,71.000,70.000,72.000,70.000,66.000,53.000,45.000,49.000,41.000,36.000,45.000,61.000,66.000,61.000,50.000,48.000,47.000,38.000,36.000,34.000,32.000,42.000,34.000,32.000,37.000,40.000,37.000}
-64.175 LMS_LASER_2D_LEFT LMS1 ID=4218,time=1225719875.822485,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=215,Range=[181]{1.003,1.011,1.019,1.027,1.033,1.039,1.047,1.047,1.060,1.073,1.071,1.081,1.098,1.109,1.115,1.118,1.128,1.146,1.157,1.166,1.185,1.193,1.204,1.222,1.233,1.255,1.268,1.279,1.296,1.319,1.330,1.348,1.378,1.395,1.416,1.424,1.449,1.468,1.487,1.514,1.548,1.560,1.589,1.620,1.651,1.688,1.709,1.738,1.757,1.812,1.836,1.885,1.922,1.958,2.005,2.048,2.085,2.132,2.178,2.265,2.315,2.371,2.456,2.525,2.567,2.582,2.587,2.668,2.764,2.808,2.889,2.955,3.007,3.107,3.221,3.353,3.461,3.576,3.724,3.832,3.908,3.887,3.876,3.900,3.933,3.954,3.961,3.964,3.951,3.973,3.967,3.963,3.993,4.034,4.062,4.062,4.073,4.090,4.101,4.103,4.104,4.114,4.107,4.107,4.107,4.114,4.113,4.113,4.123,4.122,4.131,4.137,4.143,4.157,4.166,4.174,4.174,4.182,4.190,4.198,4.208,4.214,4.229,4.240,4.249,4.258,4.276,4.278,4.292,4.318,4.333,4.343,4.355,4.366,4.382,4.390,4.407,4.425,4.442,4.461,4.480,4.492,4.510,4.528,4.545,4.565,4.592,4.612,4.627,4.645,4.672,4.696,4.729,4.753,4.776,4.793,3.122,2.967,2.945,2.936,2.941,2.940,2.953,3.077,3.073,5.090,5.120,5.158,5.200,5.233,5.268,5.303,5.336,5.365,4.836,4.812,4.690,5.410,5.463,4.725,4.817},Reflectance=[181]{35.000,40.000,37.000,40.000,43.000,46.000,45.000,46.000,39.000,45.000,46.000,46.000,45.000,43.000,45.000,48.000,48.000,44.000,46.000,50.000,43.000,43.000,49.000,44.000,45.000,48.000,46.000,47.000,47.000,49.000,46.000,46.000,43.000,39.000,45.000,53.000,49.000,53.000,54.000,55.000,54.000,59.000,53.000,48.000,50.000,50.000,51.000,52.000,57.000,53.000,49.000,46.000,48.000,52.000,54.000,50.000,55.000,61.000,55.000,44.000,53.000,50.000,44.000,52.000,55.000,53.000,55.000,51.000,50.000,50.000,48.000,48.000,56.000,50.000,56.000,57.000,57.000,59.000,64.000,59.000,52.000,61.000,68.000,72.000,74.000,75.000,75.000,69.000,67.000,69.000,67.000,68.000,70.000,71.000,74.000,77.000,75.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,80.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,110.000,78.000,79.000,79.000,78.000,77.000,76.000,108.000,6.000,74.000,73.000,71.000,71.000,70.000,70.000,67.000,69.000,64.000,83.000,81.000,69.000,69.000,61.000,65.000,76.000}
-64.191 DESIRED_THRUST iJoystick 85.5708487197
-64.191 DESIRED_RUDDER iJoystick 0
-64.195 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.2307,20.2157,-0.9567},Vel=[3x1]{-0.8306,-0.5856,-5.6410},Raw=[2x1]{22.6152,-0.9567},time=1225719875.84250831604004,Speed=1.01632545778453,Pitch=0.03813701347526,Roll=0.00224335373384,PitchDot=0.01121676866919,RollDot=0.00085247441886
-64.195 ODOMETRY_POSE iPlatform Pose=[3x1]{6.2307,20.2157,-0.9570},Vel=[3x1]{-0.8306,-0.5856,0.6422},Raw=[2x1]{22.6152,-0.9567},time=1225719875.8425,Speed=1.0163,Pitch=0.0201,Roll=0.0325,PitchDot=0.0095,RollDot=-0.0060
-63.823 IRELAYBOX_STATUS iRelayBox AppErrorFlag=false,Uptime=64.1452,MOOSName=iRelayBox,Publishing=IRELAYBOX_STATUS,RELAYBOX_STATUS,Subscribing=RELAYBOX_CMD,
-63.823 RELAYBOX_STATUS iRelayBox LADYBUG is OFF,LMS1 is ON,LMS2 is ON,P10 is OFF,P11 is OFF,P12 is OFF,P13 is OFF,P14 is OFF,P15 is OFF,P16 is OFF,P5 is OFF,P6 is OFF,P7 is OFF,P8 is OFF,P9 is OFF,PANTILT is ON,
-64.174 ICAMERABUMBLEBEE_STATUS iCameraBumbleBee AppErrorFlag=false,Uptime=-1545.07,MOOSName=iCameraBumbleBee,Publishing=ICAMERABUMBLEBEE_STATUS,Subscribing=CAMERA_COMMAND,LOGGER_DIRECTORY,MARGE_ODOMETRY,NAV_POSE,SET_INTERPOSE_COMMAND,
-64.187 LMS_LASER_2D_LEFT LMS1 ID=4219,time=1225719875.835821,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=216,Range=[181]{1.008,1.017,1.019,1.024,1.034,1.039,1.043,1.047,1.056,1.076,1.080,1.087,1.090,1.102,1.112,1.118,1.130,1.142,1.154,1.169,1.181,1.208,1.208,1.232,1.238,1.259,1.269,1.276,1.301,1.308,1.337,1.349,1.377,1.391,1.405,1.417,1.448,1.469,1.486,1.513,1.542,1.557,1.599,1.629,1.652,1.685,1.715,1.735,1.760,1.809,1.848,1.881,1.936,1.967,2.014,2.046,2.083,2.132,2.177,2.266,2.316,2.389,2.457,2.518,2.542,2.575,2.597,2.693,2.781,2.815,2.886,2.963,3.027,3.138,3.240,3.362,3.462,3.562,3.732,3.868,3.904,3.885,3.875,3.902,3.934,3.954,3.961,3.956,3.951,3.977,3.968,3.966,3.995,4.035,4.064,4.060,4.076,4.092,4.101,4.104,4.105,4.104,4.105,4.096,4.104,4.111,4.112,4.114,4.122,4.123,4.131,4.132,4.140,4.157,4.176,4.174,4.167,4.183,4.191,4.191,4.208,4.215,4.231,4.242,4.249,4.265,4.267,4.284,4.304,4.325,4.333,4.343,4.355,4.366,4.382,4.399,4.416,4.433,4.443,4.462,4.483,4.491,4.519,4.536,4.545,4.575,4.597,4.612,4.627,4.655,4.671,4.696,4.736,4.751,4.772,4.802,3.137,2.976,2.944,2.940,2.935,2.939,2.954,3.074,3.000,5.092,5.124,5.159,5.200,5.232,5.266,5.302,5.344,5.238,4.839,4.946,4.814,5.406,5.489,4.728,4.790},Reflectance=[181]{39.000,39.000,40.000,43.000,39.000,42.000,44.000,46.000,46.000,43.000,46.000,44.000,42.000,48.000,44.000,48.000,46.000,47.000,44.000,48.000,41.000,45.000,45.000,41.000,44.000,46.000,47.000,50.000,53.000,49.000,50.000,51.000,51.000,53.000,52.000,54.000,52.000,54.000,57.000,54.000,55.000,58.000,50.000,52.000,50.000,52.000,53.000,55.000,58.000,52.000,50.000,49.000,45.000,49.000,54.000,53.000,55.000,61.000,54.000,46.000,50.000,45.000,45.000,57.000,56.000,54.000,56.000,50.000,50.000,53.000,51.000,48.000,49.000,51.000,57.000,53.000,58.000,61.000,65.000,56.000,53.000,60.000,67.000,73.000,75.000,75.000,75.000,69.000,67.000,70.000,67.000,69.000,70.000,72.000,75.000,76.000,75.000,77.000,78.000,78.000,79.000,78.000,79.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,78.000,79.000,78.000,78.000,77.000,76.000,77.000,76.000,94.000,78.000,79.000,79.000,79.000,77.000,77.000,105.000,22.000,72.000,71.000,72.000,71.000,70.000,69.000,67.000,68.000,66.000,77.000,80.000,77.000,68.000,57.000,70.000,78.000}
-64.198 LMS_LASER_2D_RIGHT LMS2 ID=4092,time=1225719875.841326,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=181,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.829,18.191,15.453,12.664,10.787,9.730,8.925,8.095,7.358,6.783,6.244,5.850,5.450,5.103,4.863,4.536,4.301,4.091,3.840,3.654,3.492,3.298,3.196,3.044,2.941,2.829,2.723,2.643,2.541,2.460,2.372,2.292,2.192,2.130,2.050,1.995,1.942,1.881,1.835,1.785,1.757,1.719,1.683,1.635,1.576,1.561,1.534,1.501,1.471,1.431,1.407,1.379,1.354,1.341,1.322,1.297,1.278,1.261,1.236,1.226,1.208,1.191,1.175,1.158,1.157,1.162,1.164,1.172,1.188,1.185,1.176,1.179,1.159,1.151,1.172,1.165,1.147,1.135,1.125,1.077,1.059,1.047,1.074,1.027,1.020,1.007,1.000,1.009},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,45.000,20.000,116.000,110.000,82.000,63.000,57.000,57.000,54.000,62.000,66.000,67.000,69.000,70.000,70.000,72.000,73.000,74.000,75.000,77.000,79.000,78.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,75.000,77.000,79.000,78.000,73.000,78.000,80.000,80.000,79.000,78.000,78.000,78.000,79.000,78.000,74.000,74.000,77.000,75.000,71.000,70.000,73.000,70.000,71.000,73.000,71.000,69.000,69.000,71.000,72.000,70.000,64.000,60.000,52.000,44.000,38.000,34.000,51.000,61.000,57.000,45.000,49.000,49.000,47.000,34.000,26.000,26.000,27.000,38.000,28.000,34.000,38.000,39.000,36.000}
-64.210 LMS_LASER_2D_RIGHT LMS2 ID=4093,time=1225719875.854666,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=182,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.728,18.019,14.950,12.302,10.579,9.614,8.761,7.947,7.217,6.625,6.189,5.759,5.389,5.024,4.808,4.500,4.247,4.029,3.753,3.616,3.456,3.275,3.169,3.033,2.932,2.812,2.714,2.625,2.523,2.442,2.345,2.258,2.190,2.113,2.059,1.965,1.894,1.858,1.829,1.791,1.749,1.714,1.678,1.601,1.565,1.553,1.535,1.483,1.439,1.423,1.400,1.375,1.356,1.332,1.323,1.311,1.287,1.252,1.236,1.217,1.208,1.182,1.168,1.158,1.156,1.154,1.171,1.176,1.171,1.178,1.175,1.180,1.184,1.169,1.165,1.154,1.140,1.128,1.123,1.074,1.067,1.064,1.051,1.017,1.010,0.998,1.000,0.997},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,45.000,53.000,117.000,107.000,81.000,60.000,56.000,54.000,56.000,63.000,65.000,68.000,69.000,70.000,71.000,72.000,73.000,75.000,75.000,78.000,79.000,79.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,72.000,75.000,80.000,79.000,78.000,79.000,78.000,78.000,77.000,77.000,79.000,79.000,76.000,72.000,73.000,75.000,76.000,75.000,72.000,72.000,75.000,71.000,72.000,74.000,72.000,69.000,71.000,73.000,72.000,67.000,64.000,52.000,38.000,35.000,34.000,32.000,35.000,41.000,34.000,37.000,42.000,49.000,51.000,36.000,27.000,29.000,29.000,30.000,26.000,31.000,36.000,39.000,36.000}
-64.215 DESIRED_THRUST iJoystick 85.5708487197
-64.215 DESIRED_RUDDER iJoystick 0
-64.231 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.2560,20.2335,-0.9546},Vel=[3x1]{-0.8532,-0.6043,-6.2821},Raw=[2x1]{22.6461,-0.9546},time=1225719875.87872147560120,Speed=1.04553021231857,Pitch=0.03813701347526,Roll=0.00448670746768,PitchDot=-0.00897341493535,RollDot=0.00116654394160
-64.231 ODOMETRY_POSE iPlatform Pose=[3x1]{6.2560,20.2335,-0.9548},Vel=[3x1]{-0.8532,-0.6043,0.0011},Raw=[2x1]{22.6461,-0.9546},time=1225719875.8787,Speed=1.0455,Pitch=0.0184,Roll=0.0337,PitchDot=-0.0090,RollDot=0.0012
-64.198 LMS_LASER_2D_LEFT LMS1 ID=4220,time=1225719875.849154,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=217,Range=[181]{1.011,1.017,1.020,1.024,1.033,1.041,1.050,1.047,1.064,1.072,1.081,1.085,1.101,1.107,1.122,1.126,1.136,1.156,1.157,1.178,1.191,1.198,1.216,1.227,1.242,1.255,1.272,1.286,1.301,1.322,1.339,1.361,1.376,1.396,1.412,1.433,1.452,1.471,1.492,1.524,1.546,1.567,1.609,1.637,1.666,1.696,1.711,1.741,1.766,1.801,1.859,1.889,1.937,1.975,2.015,2.070,2.102,2.148,2.197,2.277,2.325,2.402,2.473,2.518,2.547,2.576,2.608,2.723,2.801,2.844,2.900,2.982,3.049,3.166,3.248,3.392,3.469,3.587,3.758,3.884,3.909,3.879,3.882,3.912,3.945,3.956,3.956,3.955,3.965,3.976,3.967,3.968,4.009,4.044,4.064,4.058,4.085,4.094,4.104,4.105,4.105,4.112,4.104,4.107,4.113,4.110,4.113,4.122,4.122,4.131,4.131,4.141,4.152,4.167,4.175,4.174,4.174,4.183,4.198,4.197,4.208,4.223,4.231,4.242,4.250,4.266,4.278,4.286,4.301,4.326,4.333,4.343,4.355,4.373,4.392,4.399,4.415,4.434,4.442,4.462,4.481,4.501,4.519,4.537,4.556,4.576,4.603,4.617,4.636,4.654,4.680,4.716,4.738,4.762,4.779,3.185,3.119,2.983,2.944,2.932,2.927,2.942,2.954,3.089,5.072,5.102,5.135,5.174,5.208,5.241,5.273,5.314,5.350,5.383,4.907,4.988,5.419,5.409,4.993,4.730,4.765},Reflectance=[181]{40.000,39.000,41.000,43.000,43.000,43.000,43.000,46.000,45.000,45.000,46.000,43.000,43.000,46.000,46.000,47.000,44.000,45.000,46.000,48.000,46.000,46.000,46.000,43.000,45.000,48.000,48.000,45.000,53.000,51.000,50.000,52.000,51.000,52.000,52.000,53.000,54.000,55.000,60.000,55.000,53.000,55.000,51.000,51.000,48.000,53.000,56.000,54.000,57.000,52.000,54.000,48.000,45.000,48.000,51.000,52.000,56.000,57.000,52.000,55.000,53.000,48.000,49.000,62.000,58.000,55.000,57.000,52.000,51.000,51.000,49.000,49.000,47.000,55.000,57.000,55.000,66.000,60.000,64.000,52.000,56.000,63.000,69.000,73.000,75.000,76.000,74.000,69.000,69.000,70.000,67.000,70.000,69.000,72.000,75.000,75.000,75.000,78.000,78.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,32.000,81.000,78.000,78.000,79.000,79.000,78.000,77.000,111.000,72.000,72.000,72.000,71.000,70.000,70.000,69.000,67.000,67.000,62.000,77.000,78.000,64.000,66.000,63.000,77.000,75.000}
-64.222 LMS_LASER_2D_RIGHT LMS2 ID=4094,time=1225719875.868004,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=183,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.901,16.884,14.138,11.774,10.295,9.328,8.538,7.767,7.108,6.520,6.098,5.664,5.310,4.963,4.707,4.429,4.171,3.950,3.732,3.557,3.396,3.249,3.121,3.010,2.892,2.787,2.664,2.596,2.495,2.407,2.320,2.239,2.165,2.103,2.032,1.957,1.914,1.847,1.812,1.776,1.732,1.696,1.659,1.577,1.551,1.543,1.527,1.472,1.440,1.418,1.391,1.366,1.343,1.324,1.315,1.297,1.277,1.244,1.228,1.216,1.206,1.182,1.162,1.156,1.150,1.147,1.165,1.168,1.171,1.174,1.174,1.174,1.168,1.139,1.133,1.151,1.130,1.120,1.077,1.062,1.064,1.081,1.031,1.003,1.005,0.997,0.995,1.003},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,26.000,92.000,114.000,93.000,72.000,60.000,56.000,55.000,58.000,64.000,66.000,68.000,69.000,70.000,71.000,72.000,74.000,75.000,76.000,79.000,78.000,80.000,79.000,81.000,81.000,80.000,81.000,80.000,80.000,80.000,81.000,81.000,80.000,80.000,77.000,73.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,75.000,76.000,78.000,79.000,76.000,74.000,75.000,75.000,76.000,74.000,74.000,74.000,73.000,69.000,72.000,74.000,70.000,67.000,70.000,75.000,75.000,71.000,66.000,57.000,50.000,45.000,40.000,34.000,34.000,31.000,29.000,29.000,41.000,52.000,35.000,26.000,27.000,29.000,38.000,27.000,27.000,31.000,36.000,40.000,37.000}
-64.222 LMS_LASER_2D_LEFT LMS1 ID=4221,time=1225719875.862498,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=218,Range=[181]{1.004,1.016,1.016,1.032,1.031,1.041,1.051,1.056,1.065,1.072,1.082,1.094,1.105,1.118,1.122,1.137,1.148,1.160,1.170,1.182,1.187,1.208,1.227,1.235,1.251,1.260,1.280,1.295,1.320,1.334,1.351,1.361,1.383,1.391,1.418,1.434,1.452,1.479,1.505,1.525,1.555,1.583,1.608,1.641,1.663,1.699,1.718,1.742,1.772,1.803,1.843,1.902,1.947,1.982,2.027,2.079,2.106,2.156,2.226,2.287,2.337,2.431,2.483,2.524,2.567,2.576,2.619,2.746,2.813,2.850,2.914,2.994,3.063,3.186,3.276,3.424,3.469,3.682,3.791,3.898,3.904,3.879,3.890,3.923,3.953,3.962,3.962,3.960,3.964,3.976,3.959,3.975,4.024,4.050,4.060,4.058,4.095,4.101,4.103,4.104,4.102,4.104,4.104,4.107,4.111,4.112,4.119,4.125,4.129,4.122,4.140,4.141,4.157,4.167,4.175,4.174,4.174,4.189,4.198,4.199,4.216,4.223,4.233,4.242,4.251,4.267,4.278,4.294,4.301,4.334,4.341,4.343,4.364,4.373,4.391,4.407,4.424,4.442,4.453,4.472,4.482,4.501,4.530,4.547,4.565,4.583,4.600,4.618,4.638,4.664,4.688,4.715,4.744,4.770,4.786,3.326,3.154,2.982,2.935,2.930,2.930,2.942,2.954,3.093,5.082,5.110,5.134,5.181,5.224,5.250,5.279,5.325,5.365,5.383,5.401,4.901,5.409,5.419,4.792,4.768,4.759},Reflectance=[181]{45.000,43.000,39.000,38.000,42.000,43.000,43.000,45.000,47.000,45.000,47.000,44.000,46.000,43.000,46.000,44.000,45.000,43.000,44.000,46.000,49.000,45.000,43.000,47.000,45.000,47.000,43.000,42.000,45.000,48.000,48.000,52.000,54.000,53.000,54.000,54.000,54.000,54.000,54.000,56.000,53.000,54.000,54.000,53.000,51.000,54.000,55.000,54.000,59.000,58.000,55.000,50.000,51.000,51.000,49.000,53.000,54.000,56.000,49.000,55.000,47.000,46.000,53.000,68.000,55.000,55.000,57.000,50.000,56.000,50.000,48.000,50.000,46.000,56.000,57.000,57.000,65.000,58.000,59.000,51.000,57.000,64.000,69.000,74.000,75.000,75.000,73.000,67.000,69.000,70.000,67.000,69.000,71.000,73.000,76.000,75.000,76.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,75.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,112.000,84.000,77.000,79.000,79.000,79.000,78.000,77.000,115.000,72.000,72.000,72.000,71.000,70.000,70.000,68.000,68.000,65.000,64.000,63.000,77.000,66.000,64.000,61.000,78.000,78.000}
-64.234 LMS_LASER_2D_RIGHT LMS2 ID=4095,time=1225719875.881342,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=184,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.108,-1.000,16.376,13.301,11.365,10.080,9.153,8.386,7.558,6.864,6.411,5.981,5.587,5.211,4.917,4.630,4.376,4.134,3.932,3.697,3.534,3.361,3.231,3.094,2.992,2.866,2.762,2.647,2.572,2.477,2.380,2.285,2.238,2.154,2.066,2.015,1.958,1.898,1.847,1.813,1.760,1.716,1.680,1.650,1.579,1.544,1.537,1.507,1.472,1.445,1.423,1.385,1.359,1.339,1.317,1.306,1.279,1.252,1.233,1.227,1.216,1.191,1.174,1.166,1.142,1.140,1.154,1.152,1.164,1.168,1.175,1.165,1.166,1.148,1.136,1.112,1.121,1.125,1.086,1.068,1.056,1.048,1.044,1.031,1.015,1.002,1.002,1.001,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,0.000,108.000,122.000,87.000,67.000,59.000,56.000,57.000,59.000,60.000,66.000,67.000,69.000,70.000,71.000,73.000,74.000,75.000,76.000,78.000,78.000,80.000,79.000,80.000,81.000,81.000,81.000,81.000,80.000,80.000,81.000,80.000,80.000,76.000,79.000,79.000,79.000,79.000,80.000,80.000,79.000,79.000,78.000,76.000,76.000,77.000,75.000,75.000,75.000,76.000,75.000,72.000,69.000,74.000,76.000,72.000,72.000,75.000,74.000,69.000,70.000,71.000,70.000,73.000,70.000,64.000,58.000,49.000,43.000,38.000,34.000,31.000,29.000,29.000,27.000,29.000,34.000,27.000,26.000,26.000,26.000,26.000,26.000,27.000,32.000,37.000,39.000,34.000}
-64.239 DESIRED_THRUST iJoystick 85.5708487197
-64.239 DESIRED_RUDDER iJoystick 0
-64.235 LMS_LASER_2D_LEFT LMS1 ID=4222,time=1225719875.875841,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=219,Range=[181]{1.004,1.020,1.029,1.037,1.041,1.047,1.056,1.067,1.068,1.077,1.084,1.098,1.111,1.120,1.118,1.133,1.147,1.166,1.169,1.188,1.194,1.212,1.227,1.240,1.259,1.268,1.293,1.300,1.312,1.331,1.352,1.369,1.384,1.401,1.416,1.436,1.462,1.480,1.512,1.537,1.567,1.593,1.619,1.656,1.680,1.698,1.723,1.752,1.766,1.798,1.837,1.914,1.961,1.993,2.038,2.088,2.133,2.188,2.241,2.295,2.378,2.445,2.496,2.526,2.578,2.580,2.638,2.762,2.830,2.859,2.934,2.997,3.073,3.215,3.330,3.450,3.487,3.719,3.859,3.913,3.894,3.881,3.897,3.933,3.954,3.972,3.962,3.955,3.976,3.982,3.969,3.982,4.029,4.058,4.060,4.064,4.099,4.101,4.104,4.105,4.114,4.113,4.113,4.105,4.113,4.122,4.121,4.122,4.129,4.131,4.143,4.149,4.158,4.166,4.181,4.175,4.183,4.191,4.198,4.208,4.216,4.231,4.235,4.243,4.258,4.269,4.286,4.294,4.311,4.336,4.344,4.352,4.364,4.382,4.391,4.415,4.425,4.443,4.460,4.473,4.491,4.511,4.528,4.545,4.576,4.592,4.609,4.619,4.644,4.671,4.698,4.722,4.752,4.778,4.794,3.287,3.180,2.981,2.935,2.930,2.927,2.940,2.951,3.107,5.083,5.121,5.145,5.198,5.224,5.265,5.293,5.335,5.383,5.383,5.428,5.454,5.414,5.187,4.727,4.741,4.751},Reflectance=[181]{46.000,41.000,41.000,40.000,43.000,45.000,42.000,43.000,43.000,44.000,48.000,45.000,44.000,44.000,48.000,47.000,49.000,42.000,43.000,44.000,43.000,48.000,43.000,46.000,45.000,45.000,37.000,49.000,46.000,51.000,52.000,52.000,50.000,54.000,53.000,55.000,55.000,55.000,54.000,53.000,55.000,55.000,51.000,52.000,50.000,54.000,58.000,59.000,63.000,68.000,64.000,48.000,49.000,49.000,46.000,50.000,54.000,55.000,51.000,55.000,41.000,43.000,55.000,66.000,55.000,56.000,58.000,49.000,52.000,50.000,53.000,55.000,46.000,57.000,55.000,61.000,63.000,59.000,55.000,50.000,56.000,69.000,71.000,74.000,75.000,76.000,71.000,69.000,70.000,69.000,68.000,69.000,70.000,73.000,76.000,75.000,77.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,75.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,109.000,90.000,79.000,79.000,79.000,79.000,77.000,76.000,119.000,72.000,73.000,72.000,70.000,70.000,69.000,67.000,68.000,62.000,65.000,63.000,61.000,67.000,72.000,74.000,73.000,80.000}
-64.246 LMS_LASER_2D_RIGHT LMS2 ID=4096,time=1225719875.894678,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=185,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.408,-1.000,15.669,12.914,10.985,9.837,8.953,8.187,7.405,6.700,6.313,5.859,5.468,5.120,4.846,4.561,4.301,4.065,3.876,3.654,3.492,3.324,3.194,3.078,2.959,2.840,2.723,2.652,2.532,2.435,2.364,2.286,2.219,2.127,2.067,1.999,1.950,1.889,1.841,1.795,1.747,1.707,1.680,1.635,1.584,1.544,1.520,1.501,1.465,1.440,1.410,1.374,1.344,1.324,1.306,1.297,1.279,1.252,1.242,1.219,1.200,1.183,1.159,1.153,1.146,1.141,1.154,1.149,1.167,1.167,1.180,1.160,1.157,1.153,1.125,1.119,1.127,1.129,1.083,1.068,1.059,1.052,1.040,1.016,1.028,1.012,0.987,0.997,0.983},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,17.000,0.000,118.000,113.000,85.000,64.000,58.000,55.000,56.000,56.000,63.000,66.000,69.000,70.000,70.000,71.000,74.000,74.000,76.000,77.000,76.000,78.000,79.000,80.000,81.000,81.000,80.000,80.000,80.000,81.000,81.000,81.000,80.000,79.000,79.000,79.000,79.000,79.000,80.000,80.000,78.000,79.000,79.000,79.000,78.000,76.000,74.000,73.000,72.000,74.000,75.000,75.000,74.000,73.000,74.000,73.000,72.000,72.000,75.000,74.000,72.000,71.000,72.000,74.000,75.000,72.000,65.000,57.000,46.000,38.000,37.000,33.000,31.000,31.000,27.000,28.000,31.000,35.000,27.000,26.000,26.000,26.000,27.000,28.000,30.000,32.000,34.000,38.000,33.000}
-64.246 LMS_LASER_2D_LEFT LMS1 ID=4223,time=1225719875.889182,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=220,Range=[181]{1.020,1.022,1.026,1.028,1.039,1.044,1.058,1.060,1.073,1.076,1.087,1.101,1.114,1.125,1.131,1.147,1.152,1.158,1.174,1.193,1.208,1.212,1.225,1.240,1.254,1.277,1.293,1.312,1.319,1.338,1.356,1.364,1.392,1.401,1.424,1.443,1.470,1.490,1.520,1.547,1.575,1.595,1.626,1.659,1.670,1.700,1.726,1.760,1.785,1.827,1.857,1.925,1.964,2.004,2.055,2.099,2.155,2.195,2.261,2.296,2.398,2.461,2.509,2.545,2.585,2.597,2.670,2.777,2.842,2.883,2.960,3.025,3.103,3.241,3.378,3.461,3.544,3.760,3.902,3.910,3.894,3.885,3.910,3.943,3.954,3.968,3.965,3.964,3.983,3.970,3.966,4.001,4.043,4.064,4.061,4.084,4.100,4.102,4.104,4.113,4.112,4.113,4.104,4.113,4.112,4.120,4.122,4.130,4.129,4.140,4.140,4.152,4.158,4.167,4.174,4.175,4.191,4.199,4.197,4.208,4.224,4.231,4.243,4.252,4.259,4.278,4.286,4.295,4.318,4.337,4.342,4.362,4.375,4.392,4.400,4.416,4.433,4.452,4.460,4.483,4.503,4.519,4.537,4.555,4.575,4.596,4.609,4.636,4.655,4.681,4.697,4.737,4.760,4.779,3.201,3.293,3.160,2.989,2.938,2.932,2.935,2.945,2.959,2.988,5.094,5.129,5.160,5.215,5.241,5.271,5.303,5.341,5.392,5.383,5.445,5.445,5.409,4.902,4.782,4.693,4.751},Reflectance=[181]{40.000,42.000,40.000,34.000,45.000,40.000,43.000,39.000,45.000,43.000,44.000,43.000,41.000,42.000,45.000,41.000,43.000,47.000,45.000,43.000,42.000,48.000,46.000,46.000,48.000,45.000,41.000,45.000,53.000,54.000,54.000,53.000,54.000,54.000,53.000,54.000,54.000,55.000,53.000,54.000,55.000,55.000,54.000,53.000,54.000,55.000,59.000,58.000,58.000,60.000,61.000,52.000,51.000,50.000,46.000,51.000,52.000,54.000,55.000,56.000,45.000,43.000,62.000,65.000,55.000,60.000,55.000,48.000,50.000,50.000,50.000,55.000,48.000,58.000,49.000,62.000,61.000,58.000,52.000,52.000,60.000,70.000,73.000,75.000,75.000,75.000,69.000,69.000,72.000,68.000,69.000,69.000,71.000,75.000,76.000,75.000,77.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,78.000,78.000,77.000,76.000,77.000,22.000,115.000,89.000,82.000,79.000,79.000,78.000,77.000,76.000,55.000,73.000,73.000,72.000,70.000,70.000,68.000,67.000,67.000,62.000,64.000,64.000,62.000,66.000,68.000,75.000,74.000,80.000}
-64.258 LMS_LASER_2D_RIGHT LMS2 ID=4097,time=1225719875.908012,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=186,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.310,17.917,14.940,12.364,10.630,9.615,8.660,7.946,7.234,6.647,6.172,5.776,5.389,5.076,4.782,4.509,4.230,4.011,3.774,3.620,3.414,3.275,3.162,3.053,2.924,2.804,2.715,2.606,2.514,2.424,2.337,2.274,2.209,2.111,2.053,1.990,1.940,1.873,1.832,1.788,1.738,1.704,1.650,1.613,1.577,1.552,1.530,1.486,1.471,1.447,1.394,1.374,1.348,1.333,1.315,1.312,1.285,1.251,1.242,1.218,1.193,1.181,1.159,1.153,1.146,1.140,1.147,1.147,1.160,1.163,1.146,1.161,1.155,1.136,1.137,1.151,1.135,1.123,1.118,1.064,1.056,1.048,1.034,1.047,1.016,1.001,0.996,0.994,0.986},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,42.000,49.000,115.000,107.000,80.000,60.000,60.000,54.000,56.000,61.000,65.000,66.000,69.000,70.000,71.000,72.000,74.000,75.000,77.000,77.000,77.000,79.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,80.000,80.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,75.000,75.000,70.000,69.000,75.000,76.000,74.000,73.000,67.000,60.000,69.000,75.000,74.000,74.000,75.000,74.000,74.000,75.000,71.000,66.000,56.000,47.000,35.000,31.000,33.000,31.000,29.000,31.000,43.000,51.000,49.000,41.000,27.000,26.000,26.000,27.000,32.000,29.000,35.000,38.000,39.000,35.000}
-64.263 DESIRED_THRUST iJoystick 85.5708487197
-64.263 DESIRED_RUDDER iJoystick 0
-64.267 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.2812,20.2514,-0.9521},Vel=[3x1]{-0.8160,-0.5810,-8.8462},Raw=[2x1]{22.6771,-0.9521},time=1225719875.91447353363037,Speed=1.00172308051751,Pitch=0.03589365974142,Roll=0.00897341493535,PitchDot=0.00673006120152,RollDot=0.00141331285232
-64.267 ODOMETRY_POSE iPlatform Pose=[3x1]{6.2812,20.2514,-0.9522},Vel=[3x1]{-0.8160,-0.5810,-2.5630},Raw=[2x1]{22.6771,-0.9521},time=1225719875.9145,Speed=1.0017,Pitch=0.0135,Roll=0.0344,PitchDot=-0.0064,RollDot=0.0025
-64.287 DESIRED_THRUST iJoystick 85.5708487197
-64.287 DESIRED_RUDDER iJoystick 0
-64.258 LMS_LASER_2D_LEFT LMS1 ID=4224,time=1225719875.902521,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=221,Range=[181]{1.020,1.020,1.034,1.038,1.046,1.057,1.059,1.060,1.073,1.090,1.091,1.104,1.120,1.124,1.135,1.149,1.149,1.167,1.181,1.196,1.216,1.219,1.233,1.247,1.264,1.273,1.295,1.306,1.323,1.338,1.346,1.373,1.391,1.401,1.435,1.452,1.470,1.498,1.521,1.556,1.577,1.597,1.625,1.669,1.681,1.710,1.730,1.763,1.813,1.848,1.868,1.936,1.979,2.024,2.075,2.121,2.169,2.216,2.267,2.295,2.401,2.480,2.527,2.559,2.576,2.603,2.698,2.785,2.841,2.889,2.974,3.016,3.131,3.278,3.402,3.481,3.620,3.789,3.906,3.910,3.887,3.880,3.919,3.954,3.962,3.965,3.965,3.962,3.987,3.970,3.976,4.010,4.043,4.075,4.059,4.097,4.099,4.104,4.104,4.116,4.116,4.116,4.113,4.113,4.121,4.122,4.119,4.131,4.138,4.140,4.149,4.150,4.157,4.167,4.174,4.182,4.183,4.197,4.208,4.208,4.230,4.241,4.243,4.252,4.269,4.278,4.298,4.305,4.327,4.345,4.351,4.365,4.373,4.393,4.407,4.425,4.441,4.453,4.472,4.491,4.509,4.527,4.546,4.565,4.585,4.602,4.618,4.637,4.663,4.691,4.715,4.747,4.770,4.787,4.813,3.304,3.136,3.008,2.938,2.933,2.935,2.944,2.957,2.993,5.107,5.140,5.174,5.216,5.248,5.281,5.316,5.355,5.401,5.401,5.454,5.428,5.022,4.832,4.744,4.675,4.779},Reflectance=[181]{41.000,40.000,40.000,37.000,40.000,42.000,48.000,48.000,46.000,45.000,42.000,44.000,44.000,45.000,48.000,45.000,46.000,47.000,46.000,44.000,45.000,48.000,46.000,49.000,49.000,49.000,45.000,48.000,51.000,54.000,53.000,53.000,53.000,58.000,54.000,54.000,54.000,55.000,54.000,54.000,56.000,53.000,54.000,53.000,54.000,55.000,62.000,60.000,54.000,58.000,58.000,50.000,45.000,43.000,47.000,49.000,51.000,48.000,54.000,59.000,48.000,48.000,61.000,59.000,55.000,59.000,56.000,52.000,49.000,48.000,56.000,59.000,52.000,55.000,51.000,58.000,55.000,55.000,51.000,52.000,64.000,67.000,72.000,75.000,75.000,74.000,69.000,68.000,70.000,68.000,70.000,69.000,71.000,75.000,76.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,79.000,77.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,78.000,78.000,79.000,78.000,77.000,77.000,77.000,77.000,117.000,90.000,87.000,79.000,80.000,78.000,76.000,75.000,50.000,74.000,74.000,71.000,70.000,69.000,68.000,68.000,66.000,62.000,63.000,63.000,64.000,77.000,70.000,72.000,74.000,82.000}
-64.270 LMS_LASER_2D_RIGHT LMS2 ID=4098,time=1225719875.921346,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=187,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.075,17.018,14.080,11.833,10.340,9.358,8.513,7.784,7.098,6.537,6.052,5.690,5.301,4.998,4.698,4.412,4.162,3.925,3.757,3.557,3.383,3.269,3.133,3.013,2.868,2.779,2.679,2.569,2.487,2.406,2.309,2.256,2.192,2.093,2.034,1.977,1.924,1.866,1.816,1.779,1.728,1.668,1.632,1.596,1.572,1.540,1.509,1.488,1.466,1.430,1.404,1.371,1.348,1.324,1.298,1.287,1.276,1.253,1.227,1.209,1.184,1.175,1.157,1.141,1.134,1.132,1.130,1.137,1.160,1.160,1.164,1.153,1.148,1.139,1.141,1.133,1.116,1.109,1.104,1.084,1.054,1.042,1.028,1.021,1.014,1.001,0.993,0.987,0.996},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,23.000,80.000,118.000,99.000,74.000,60.000,57.000,54.000,57.000,63.000,67.000,68.000,69.000,70.000,71.000,72.000,74.000,75.000,76.000,76.000,77.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,78.000,78.000,78.000,78.000,79.000,78.000,76.000,78.000,76.000,72.000,72.000,74.000,75.000,74.000,74.000,70.000,67.000,72.000,73.000,71.000,72.000,71.000,70.000,72.000,73.000,70.000,67.000,59.000,43.000,36.000,33.000,31.000,30.000,29.000,31.000,53.000,61.000,58.000,52.000,31.000,27.000,26.000,27.000,28.000,29.000,35.000,37.000,37.000,40.000}
-64.271 LMS_LASER_2D_LEFT LMS1 ID=4225,time=1225719875.915861,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=222,Range=[181]{1.017,1.035,1.035,1.043,1.050,1.048,1.060,1.067,1.073,1.084,1.092,1.109,1.118,1.131,1.140,1.155,1.154,1.175,1.191,1.196,1.212,1.223,1.234,1.251,1.270,1.276,1.296,1.314,1.328,1.344,1.356,1.373,1.392,1.416,1.443,1.459,1.485,1.507,1.547,1.563,1.584,1.617,1.644,1.670,1.692,1.723,1.739,1.779,1.837,1.857,1.880,1.953,1.991,2.043,2.088,2.132,2.184,2.233,2.284,2.322,2.425,2.497,2.527,2.578,2.581,2.631,2.725,2.807,2.855,2.911,2.999,3.052,3.168,3.311,3.437,3.492,3.680,3.854,3.916,3.913,3.886,3.891,3.932,3.955,3.962,3.965,3.964,3.971,3.986,3.964,3.978,4.028,4.049,4.067,4.067,4.098,4.100,4.103,4.113,4.113,4.114,4.114,4.111,4.121,4.119,4.119,4.121,4.138,4.139,4.147,4.149,4.158,4.158,4.175,4.174,4.183,4.199,4.198,4.207,4.216,4.228,4.240,4.252,4.260,4.269,4.278,4.294,4.312,4.338,4.343,4.352,4.373,4.383,4.393,4.407,4.433,4.440,4.461,4.481,4.492,4.511,4.536,4.546,4.565,4.583,4.600,4.628,4.645,4.672,4.698,4.722,4.751,4.770,4.795,4.822,3.270,3.118,3.017,2.933,2.930,2.935,2.944,3.037,3.008,5.114,5.151,5.191,5.236,5.263,5.286,5.335,5.365,5.392,5.428,5.454,5.412,4.841,4.807,4.685,4.764,4.767},Reflectance=[181]{40.000,36.000,37.000,39.000,43.000,47.000,48.000,48.000,46.000,43.000,43.000,43.000,43.000,45.000,45.000,40.000,49.000,47.000,45.000,44.000,48.000,46.000,47.000,46.000,47.000,50.000,47.000,51.000,53.000,52.000,54.000,53.000,54.000,53.000,54.000,53.000,53.000,55.000,54.000,57.000,59.000,54.000,54.000,54.000,55.000,57.000,61.000,55.000,49.000,61.000,55.000,53.000,43.000,40.000,46.000,46.000,50.000,48.000,54.000,56.000,47.000,55.000,63.000,55.000,57.000,59.000,56.000,50.000,48.000,50.000,56.000,56.000,56.000,54.000,50.000,59.000,53.000,50.000,48.000,57.000,66.000,70.000,74.000,76.000,75.000,71.000,69.000,68.000,70.000,69.000,70.000,70.000,73.000,75.000,75.000,77.000,77.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,77.000,77.000,77.000,109.000,93.000,92.000,80.000,79.000,78.000,76.000,95.000,37.000,74.000,74.000,68.000,71.000,68.000,67.000,68.000,64.000,65.000,62.000,61.000,67.000,77.000,71.000,72.000,77.000,78.000}
-64.283 LMS_LASER_2D_LEFT LMS1 ID=4226,time=1225719875.929199,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=223,Range=[181]{1.023,1.034,1.029,1.046,1.050,1.055,1.062,1.071,1.083,1.100,1.102,1.114,1.130,1.136,1.138,1.157,1.168,1.176,1.191,1.206,1.217,1.235,1.246,1.252,1.269,1.287,1.306,1.319,1.334,1.356,1.374,1.391,1.409,1.424,1.443,1.468,1.486,1.522,1.556,1.578,1.605,1.616,1.652,1.687,1.709,1.725,1.738,1.779,1.849,1.869,1.924,1.974,2.019,2.065,2.099,2.148,2.187,2.251,2.312,2.370,2.445,2.507,2.545,2.584,2.584,2.659,2.750,2.818,2.870,2.937,3.027,3.100,3.214,3.349,3.476,3.581,3.709,3.908,3.919,3.912,3.887,3.906,3.942,3.962,3.970,3.972,3.967,3.973,3.979,3.974,3.990,4.040,4.069,4.071,4.076,4.107,4.109,4.111,4.118,4.113,4.113,4.112,4.120,4.122,4.122,4.120,4.128,4.138,4.139,4.139,4.149,4.158,4.168,4.174,4.182,4.191,4.199,4.208,4.217,4.227,4.236,4.242,4.252,4.260,4.278,4.286,4.295,4.318,4.336,4.351,4.353,4.374,4.383,4.400,4.415,4.433,4.451,4.464,4.482,4.501,4.521,4.536,4.555,4.576,4.592,4.609,4.638,4.655,4.679,4.708,4.729,4.761,4.776,4.804,4.828,3.240,3.114,2.985,2.933,2.933,2.943,2.946,3.059,2.997,5.133,5.161,5.214,5.239,5.271,5.306,5.340,5.392,5.383,5.445,5.454,4.897,4.792,4.770,4.679,4.804,4.724},Reflectance=[181]{38.000,39.000,35.000,38.000,43.000,46.000,46.000,46.000,42.000,36.000,33.000,41.000,41.000,44.000,46.000,45.000,47.000,47.000,45.000,46.000,47.000,42.000,48.000,51.000,51.000,51.000,51.000,49.000,52.000,54.000,50.000,53.000,54.000,53.000,54.000,53.000,54.000,54.000,54.000,52.000,53.000,54.000,54.000,53.000,55.000,59.000,66.000,55.000,54.000,55.000,44.000,48.000,44.000,42.000,47.000,46.000,51.000,47.000,48.000,53.000,43.000,56.000,63.000,54.000,58.000,59.000,55.000,55.000,47.000,51.000,56.000,50.000,57.000,52.000,48.000,49.000,47.000,48.000,49.000,57.000,64.000,72.000,74.000,75.000,75.000,71.000,69.000,69.000,68.000,69.000,69.000,71.000,73.000,77.000,75.000,77.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,76.000,77.000,76.000,100.000,104.000,85.000,80.000,80.000,78.000,77.000,101.000,25.000,74.000,72.000,70.000,69.000,68.000,68.000,67.000,62.000,64.000,62.000,61.000,80.000,78.000,70.000,75.000,79.000,71.000}
-64.294 LMS_LASER_2D_RIGHT LMS2 ID=4099,time=1225719875.934690,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=188,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.425,-1.000,16.351,13.291,11.375,10.072,9.103,8.273,7.445,6.968,6.408,5.972,5.596,5.237,4.899,4.621,4.349,4.117,3.861,3.707,3.521,3.355,3.223,3.097,2.976,2.847,2.740,2.643,2.543,2.469,2.367,2.291,2.239,2.156,2.075,2.025,1.969,1.898,1.855,1.813,1.767,1.721,1.668,1.633,1.586,1.562,1.522,1.487,1.474,1.454,1.420,1.395,1.366,1.343,1.307,1.308,1.289,1.265,1.243,1.225,1.199,1.166,1.151,1.144,1.143,1.131,1.132,1.136,1.144,1.159,1.160,1.141,1.148,1.150,1.121,1.148,1.123,1.110,1.098,1.108,1.082,1.045,1.037,1.022,1.025,0.999,0.990,0.982,0.990,0.988},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,7.000,0.000,102.000,120.000,90.000,67.000,60.000,56.000,58.000,61.000,65.000,67.000,68.000,69.000,70.000,71.000,73.000,74.000,74.000,77.000,77.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,81.000,80.000,79.000,80.000,80.000,79.000,79.000,80.000,79.000,78.000,78.000,78.000,78.000,79.000,75.000,77.000,79.000,78.000,76.000,76.000,75.000,74.000,74.000,77.000,77.000,75.000,72.000,71.000,70.000,71.000,74.000,77.000,77.000,75.000,70.000,63.000,54.000,38.000,34.000,31.000,31.000,31.000,28.000,38.000,53.000,58.000,57.000,47.000,30.000,27.000,27.000,27.000,29.000,28.000,33.000,34.000,38.000,38.000}
-64.303 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.3143,20.2751,-0.9476},Vel=[3x1]{-0.8194,-0.5889,-4.3590},Raw=[2x1]{22.7178,-0.9476},time=1225719875.95064830780029,Speed=1.00902426915102,Pitch=0.03589365974142,Roll=0.01346012240303,PitchDot=0.00224335373384,RollDot=0.00181711652441
-64.303 ODOMETRY_POSE iPlatform Pose=[3x1]{6.3143,20.2751,-0.9475},Vel=[3x1]{-0.8194,-0.5889,1.9242},Raw=[2x1]{22.7178,-0.9476},time=1225719875.9506,Speed=1.0090,Pitch=0.0100,Roll=0.0370,PitchDot=0.0009,RollDot=-0.0027
-64.311 DESIRED_THRUST iJoystick 85.5708487197
-64.311 DESIRED_RUDDER iJoystick 0
-64.294 LMS_LASER_2D_LEFT LMS1 ID=4227,time=1225719875.942534,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=224,Range=[181]{1.026,1.034,1.035,1.051,1.047,1.064,1.072,1.080,1.059,1.096,1.097,1.119,1.129,1.140,1.151,1.166,1.174,1.182,1.191,1.211,1.225,1.233,1.258,1.261,1.278,1.298,1.306,1.331,1.336,1.356,1.383,1.400,1.418,1.436,1.459,1.479,1.505,1.530,1.547,1.572,1.606,1.635,1.662,1.683,1.707,1.730,1.748,1.825,1.859,1.902,1.939,1.982,2.030,2.069,2.112,2.166,2.221,2.274,2.340,2.388,2.462,2.518,2.563,2.576,2.605,2.715,2.775,2.830,2.888,2.967,3.034,3.133,3.265,3.397,3.502,3.600,3.776,3.916,3.912,3.901,3.885,3.911,3.945,3.962,3.976,3.971,3.965,3.989,3.981,3.977,4.008,4.047,4.073,4.070,4.085,4.110,4.112,4.111,4.122,4.112,4.113,4.122,4.119,4.120,4.122,4.128,4.129,4.138,4.139,4.148,4.149,4.168,4.175,4.178,4.189,4.190,4.191,4.208,4.216,4.230,4.239,4.250,4.260,4.269,4.286,4.295,4.301,4.327,4.343,4.352,4.367,4.374,4.390,4.408,4.425,4.440,4.459,4.475,4.491,4.509,4.528,4.545,4.565,4.576,4.592,4.618,4.646,4.664,4.690,4.715,4.745,4.768,4.785,4.814,3.113,3.303,3.114,2.967,2.933,2.930,2.942,2.955,3.078,5.102,5.142,5.179,5.222,5.255,5.284,5.317,5.355,5.401,5.392,5.454,5.437,4.754,4.773,4.708,4.826,4.847,4.742},Reflectance=[181]{40.000,39.000,40.000,40.000,34.000,45.000,45.000,41.000,30.000,34.000,32.000,35.000,44.000,45.000,43.000,42.000,42.000,46.000,46.000,48.000,46.000,46.000,41.000,47.000,47.000,48.000,51.000,51.000,53.000,54.000,54.000,53.000,51.000,47.000,53.000,54.000,54.000,54.000,54.000,53.000,53.000,54.000,54.000,55.000,58.000,61.000,63.000,48.000,50.000,50.000,47.000,47.000,38.000,49.000,48.000,46.000,45.000,46.000,44.000,53.000,48.000,61.000,61.000,55.000,60.000,56.000,51.000,52.000,52.000,56.000,55.000,49.000,53.000,49.000,47.000,50.000,45.000,48.000,49.000,60.000,68.000,73.000,75.000,75.000,75.000,71.000,69.000,71.000,69.000,70.000,69.000,72.000,75.000,76.000,75.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,76.000,77.000,29.000,108.000,119.000,83.000,80.000,79.000,78.000,77.000,109.000,72.000,74.000,70.000,69.000,69.000,69.000,68.000,66.000,61.000,63.000,63.000,64.000,77.000,78.000,71.000,71.000,79.000,69.000}
-64.306 LMS_LASER_2D_RIGHT LMS2 ID=4100,time=1225719875.948032,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=189,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.505,20.011,15.834,12.798,10.985,9.847,8.944,8.079,7.304,6.794,6.262,5.851,5.502,5.146,4.828,4.544,4.292,4.064,3.851,3.671,3.470,3.338,3.186,3.071,2.925,2.810,2.723,2.627,2.524,2.438,2.335,2.275,2.227,2.127,2.061,2.002,1.961,1.897,1.855,1.812,1.754,1.702,1.669,1.620,1.579,1.549,1.501,1.466,1.464,1.438,1.415,1.384,1.362,1.333,1.323,1.306,1.289,1.260,1.234,1.208,1.174,1.159,1.143,1.138,1.133,1.128,1.115,1.129,1.145,1.147,1.147,1.156,1.144,1.136,1.151,1.145,1.122,1.109,1.103,1.099,1.095,1.074,1.051,1.017,1.014,1.005,0.991,0.978,0.980,0.980},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,32.000,2.000,114.000,116.000,85.000,63.000,58.000,57.000,56.000,64.000,65.000,68.000,67.000,69.000,69.000,72.000,72.000,73.000,74.000,76.000,78.000,80.000,79.000,80.000,81.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,73.000,74.000,78.000,78.000,77.000,75.000,74.000,74.000,76.000,76.000,72.000,71.000,70.000,70.000,70.000,73.000,76.000,78.000,78.000,77.000,71.000,64.000,51.000,37.000,33.000,34.000,31.000,30.000,34.000,51.000,56.000,62.000,59.000,50.000,37.000,36.000,30.000,26.000,26.000,29.000,34.000,35.000,38.000,36.000}
-64.306 LMS_LASER_2D_LEFT LMS1 ID=4228,time=1225719875.955869,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=225,Range=[181]{1.022,1.035,1.039,1.050,1.027,1.073,1.073,1.077,1.063,1.098,1.104,1.130,1.132,1.148,1.157,1.166,1.179,1.189,1.208,1.217,1.231,1.247,1.261,1.268,1.280,1.292,1.317,1.336,1.347,1.365,1.380,1.401,1.425,1.455,1.461,1.486,1.505,1.555,1.558,1.582,1.617,1.644,1.671,1.688,1.716,1.751,1.770,1.830,1.876,1.919,1.946,1.988,2.035,2.085,2.133,2.174,2.232,2.294,2.356,2.391,2.486,2.527,2.572,2.581,2.617,2.709,2.788,2.855,2.900,2.984,3.061,3.163,3.309,3.436,3.542,3.664,3.806,3.924,3.913,3.900,3.896,3.928,3.954,3.962,3.975,3.969,3.970,3.989,3.969,3.982,4.022,4.057,4.076,4.068,4.103,4.109,4.109,4.108,4.119,4.118,4.120,4.125,4.118,4.120,4.129,4.130,4.139,4.139,4.148,4.148,4.158,4.167,4.174,4.185,4.187,4.197,4.199,4.208,4.226,4.229,4.248,4.251,4.260,4.277,4.286,4.294,4.311,4.335,4.343,4.354,4.365,4.383,4.398,4.408,4.427,4.442,4.458,4.474,4.491,4.511,4.537,4.555,4.565,4.586,4.599,4.628,4.645,4.672,4.690,4.723,4.745,4.774,4.795,3.147,3.132,3.179,3.104,2.947,2.933,2.930,2.941,2.952,3.095,5.115,5.150,5.191,5.231,5.260,5.291,5.324,5.365,5.401,5.410,5.454,4.937,4.732,4.745,4.665,4.848,4.840,4.721},Reflectance=[181]{42.000,40.000,42.000,39.000,29.000,42.000,45.000,32.000,29.000,34.000,33.000,41.000,45.000,45.000,45.000,42.000,44.000,46.000,45.000,47.000,46.000,40.000,38.000,46.000,48.000,49.000,49.000,53.000,54.000,54.000,52.000,54.000,54.000,38.000,50.000,54.000,54.000,50.000,55.000,54.000,54.000,54.000,54.000,54.000,54.000,54.000,59.000,50.000,45.000,46.000,47.000,46.000,37.000,44.000,42.000,44.000,42.000,45.000,52.000,55.000,54.000,65.000,61.000,57.000,62.000,61.000,53.000,48.000,50.000,57.000,56.000,46.000,46.000,45.000,48.000,46.000,47.000,47.000,54.000,59.000,69.000,73.000,75.000,75.000,74.000,70.000,68.000,69.000,68.000,71.000,71.000,72.000,75.000,76.000,76.000,77.000,77.000,77.000,78.000,77.000,78.000,79.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,78.000,79.000,79.000,78.000,77.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,77.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,76.000,77.000,15.000,32.000,16.000,117.000,79.000,80.000,79.000,78.000,76.000,117.000,74.000,74.000,68.000,69.000,67.000,69.000,68.000,64.000,64.000,62.000,63.000,78.000,76.000,72.000,69.000,72.000,77.000,70.000}
-64.319 LMS_LASER_2D_RIGHT LMS2 ID=4101,time=1225719875.961374,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=190,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.571,18.351,15.197,12.324,10.675,9.662,8.763,7.916,7.229,6.642,6.173,5.759,5.398,5.075,4.774,4.475,4.230,4.001,3.815,3.577,3.424,3.311,3.168,3.045,2.877,2.789,2.689,2.604,2.504,2.394,2.327,2.267,2.200,2.110,2.054,2.000,1.942,1.889,1.829,1.784,1.737,1.696,1.649,1.602,1.577,1.542,1.506,1.476,1.466,1.425,1.402,1.378,1.355,1.339,1.306,1.288,1.270,1.241,1.213,1.197,1.175,1.159,1.151,1.139,1.132,1.127,1.116,1.129,1.138,1.150,1.159,1.148,1.144,1.148,1.142,1.143,1.123,1.112,1.116,1.099,1.083,1.077,1.067,1.042,0.999,0.993,0.984,0.980,0.978,0.984},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,30.000,28.000,112.000,112.000,80.000,61.000,57.000,57.000,53.000,63.000,66.000,67.000,69.000,69.000,69.000,72.000,74.000,74.000,76.000,77.000,78.000,80.000,79.000,80.000,81.000,81.000,81.000,80.000,80.000,79.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,76.000,69.000,77.000,79.000,77.000,76.000,76.000,75.000,75.000,73.000,72.000,71.000,68.000,65.000,67.000,72.000,73.000,77.000,78.000,78.000,77.000,71.000,65.000,56.000,47.000,43.000,32.000,32.000,32.000,34.000,50.000,57.000,55.000,50.000,46.000,38.000,48.000,47.000,31.000,26.000,26.000,31.000,34.000,37.000,35.000}
-64.330 LMS_LASER_2D_RIGHT LMS2 ID=4102,time=1225719875.974715,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=191,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.282,17.557,14.550,11.991,10.496,9.498,8.620,7.778,7.136,6.562,6.098,5.648,5.372,4.998,4.715,4.466,4.221,3.966,3.783,3.572,3.416,3.290,3.148,3.008,2.864,2.762,2.679,2.586,2.501,2.388,2.309,2.256,2.181,2.118,2.051,1.983,1.933,1.872,1.820,1.776,1.729,1.688,1.632,1.592,1.557,1.536,1.500,1.481,1.444,1.415,1.390,1.369,1.351,1.324,1.320,1.287,1.252,1.242,1.230,1.212,1.176,1.158,1.143,1.128,1.126,1.125,1.117,1.128,1.132,1.149,1.149,1.153,1.146,1.135,1.133,1.141,1.117,1.114,1.104,1.106,1.080,1.073,1.074,1.046,1.003,0.992,0.983,0.978,0.981,0.982},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,65.000,117.000,105.000,76.000,60.000,58.000,56.000,54.000,63.000,66.000,69.000,69.000,70.000,70.000,73.000,73.000,74.000,76.000,76.000,78.000,78.000,78.000,80.000,80.000,81.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,79.000,78.000,77.000,75.000,74.000,72.000,78.000,78.000,77.000,75.000,74.000,73.000,73.000,67.000,71.000,72.000,70.000,63.000,64.000,73.000,72.000,76.000,77.000,77.000,76.000,72.000,64.000,57.000,46.000,46.000,36.000,32.000,31.000,30.000,46.000,57.000,52.000,52.000,45.000,32.000,34.000,43.000,32.000,27.000,26.000,33.000,35.000,38.000,38.000}
-64.335 DESIRED_THRUST iJoystick 85.5708487197
-64.335 DESIRED_RUDDER iJoystick 0
-64.339 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.3384,20.2925,-0.9448},Vel=[3x1]{-0.8153,-0.5895,-3.0769},Raw=[2x1]{22.7475,-0.9448},time=1225719875.98650646209717,Speed=1.00610379369761,Pitch=0.03813701347526,Roll=0.01794682987071,PitchDot=0.02243353733839,RollDot=0.00132357870296
-64.339 ODOMETRY_POSE iPlatform Pose=[3x1]{6.3384,20.2925,-0.9446},Vel=[3x1]{-0.8153,-0.5895,-3.0769},Raw=[2x1]{22.7475,-0.9448},time=1225719875.9865,Speed=1.0061,Pitch=0.0078,Roll=0.0414,PitchDot=-0.0225,RollDot=0.0001
-64.331 LMS_LASER_2D_LEFT LMS1 ID=4229,time=1225719875.969215,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=226,Range=[181]{1.031,1.043,1.048,1.055,1.056,1.044,1.076,1.052,1.068,1.087,1.119,1.130,1.144,1.145,1.152,1.169,1.182,1.198,1.204,1.220,1.236,1.250,1.254,1.273,1.290,1.305,1.313,1.333,1.350,1.370,1.388,1.400,1.417,1.465,1.473,1.494,1.523,1.554,1.573,1.596,1.616,1.636,1.671,1.690,1.723,1.770,1.786,1.839,1.885,1.937,1.968,2.001,2.042,2.092,2.132,2.190,2.247,2.300,2.363,2.409,2.490,2.535,2.583,2.585,2.628,2.718,2.787,2.875,2.909,3.009,3.085,3.177,3.338,3.451,3.553,3.690,3.820,3.928,3.913,3.896,3.894,3.938,3.962,3.971,3.974,3.967,3.973,3.993,3.969,3.990,4.032,4.067,4.076,4.068,4.104,4.100,4.112,4.110,4.108,4.121,4.119,4.116,4.121,4.121,4.130,4.127,4.140,4.140,4.149,4.150,4.149,4.166,4.177,4.185,4.187,4.197,4.205,4.216,4.231,4.237,4.249,4.252,4.270,4.279,4.286,4.306,4.322,4.337,4.343,4.354,4.373,4.381,4.400,4.417,4.434,4.451,4.461,4.481,4.491,4.517,4.538,4.554,4.575,4.586,4.601,4.628,4.646,4.671,4.698,4.722,4.751,4.775,4.796,3.110,3.177,4.879,3.107,2.945,2.932,2.938,2.939,2.950,3.098,5.116,5.154,5.198,5.239,5.270,5.299,5.329,5.383,5.392,5.428,5.454,4.796,4.764,4.735,4.745,4.948,4.868,4.750},Reflectance=[181]{42.000,37.000,38.000,38.000,33.000,29.000,43.000,29.000,29.000,31.000,37.000,40.000,40.000,44.000,48.000,43.000,45.000,46.000,49.000,48.000,43.000,45.000,48.000,49.000,48.000,51.000,51.000,52.000,51.000,48.000,52.000,53.000,54.000,40.000,48.000,53.000,47.000,53.000,54.000,53.000,54.000,55.000,54.000,55.000,54.000,51.000,54.000,46.000,50.000,45.000,44.000,44.000,35.000,43.000,46.000,44.000,41.000,45.000,51.000,55.000,56.000,64.000,58.000,59.000,63.000,65.000,56.000,46.000,50.000,57.000,55.000,49.000,47.000,49.000,49.000,45.000,46.000,49.000,58.000,64.000,71.000,73.000,75.000,75.000,74.000,69.000,69.000,70.000,70.000,71.000,71.000,73.000,75.000,76.000,76.000,77.000,78.000,78.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,79.000,79.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,76.000,77.000,24.000,27.000,76.000,122.000,79.000,79.000,79.000,77.000,75.000,120.000,74.000,72.000,68.000,69.000,68.000,68.000,67.000,61.000,65.000,62.000,62.000,77.000,75.000,69.000,59.000,64.000,75.000,76.000}
-64.342 LMS_LASER_2D_RIGHT LMS2 ID=4103,time=1225719875.988053,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=192,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.271,17.224,14.041,11.798,10.366,9.383,8.513,7.706,7.050,6.496,6.043,5.588,5.337,4.972,4.698,4.439,4.170,3.932,3.759,3.540,3.407,3.273,3.138,2.968,2.864,2.754,2.671,2.566,2.485,2.364,2.300,2.227,2.156,2.103,2.034,1.969,1.925,1.872,1.811,1.774,1.723,1.689,1.640,1.590,1.568,1.517,1.493,1.466,1.436,1.415,1.385,1.349,1.343,1.324,1.304,1.289,1.262,1.251,1.230,1.201,1.181,1.150,1.134,1.131,1.126,1.120,1.123,1.128,1.134,1.135,1.153,1.142,1.139,1.144,1.118,1.137,1.129,1.114,1.106,1.095,1.051,1.034,1.056,1.013,1.002,0.989,0.968,0.986,0.980,0.985},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,75.000,124.000,96.000,72.000,59.000,57.000,55.000,56.000,64.000,66.000,69.000,69.000,69.000,70.000,72.000,74.000,75.000,77.000,77.000,78.000,78.000,79.000,81.000,80.000,81.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,79.000,79.000,78.000,77.000,69.000,71.000,74.000,73.000,70.000,73.000,74.000,70.000,63.000,61.000,67.000,71.000,74.000,76.000,76.000,75.000,70.000,63.000,54.000,47.000,41.000,34.000,31.000,32.000,29.000,35.000,48.000,53.000,52.000,37.000,26.000,26.000,31.000,27.000,26.000,26.000,29.000,35.000,38.000,39.000}
-64.342 LMS_LASER_2D_LEFT LMS1 ID=4230,time=1225719875.982558,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=227,Range=[181]{1.033,1.043,1.042,1.054,1.062,1.073,1.073,1.051,1.076,1.085,1.126,1.128,1.142,1.149,1.152,1.167,1.190,1.198,1.211,1.225,1.233,1.250,1.261,1.282,1.295,1.304,1.326,1.337,1.356,1.380,1.392,1.409,1.425,1.457,1.481,1.499,1.525,1.561,1.580,1.607,1.616,1.641,1.665,1.695,1.718,1.767,1.808,1.853,1.887,1.938,1.978,2.016,2.063,2.096,2.153,2.203,2.258,2.313,2.380,2.424,2.510,2.559,2.594,2.587,2.646,2.730,2.784,2.877,2.930,3.004,3.099,3.210,3.357,3.457,3.577,3.724,3.842,3.929,3.913,3.887,3.901,3.940,3.961,3.971,3.971,3.970,3.977,3.986,3.973,3.994,4.038,4.067,4.068,4.076,4.105,4.103,4.112,4.109,4.119,4.119,4.119,4.113,4.121,4.128,4.128,4.139,4.138,4.139,4.149,4.158,4.157,4.167,4.174,4.179,4.187,4.197,4.203,4.214,4.223,4.238,4.251,4.258,4.269,4.278,4.286,4.306,4.321,4.336,4.342,4.363,4.373,4.382,4.399,4.418,4.432,4.452,4.463,4.482,4.501,4.519,4.537,4.555,4.577,4.595,4.610,4.637,4.654,4.680,4.699,4.732,4.752,4.776,4.805,4.827,4.855,4.885,3.116,2.949,2.932,2.935,2.939,2.958,3.098,5.129,5.162,5.209,5.235,5.281,5.306,5.337,5.398,5.392,5.437,5.454,4.795,4.756,4.733,4.771,4.997,4.868,4.783},Reflectance=[181]{39.000,44.000,43.000,40.000,37.000,34.000,46.000,29.000,30.000,31.000,39.000,40.000,42.000,46.000,48.000,47.000,45.000,46.000,48.000,46.000,46.000,46.000,47.000,49.000,46.000,50.000,49.000,49.000,50.000,49.000,50.000,54.000,54.000,44.000,48.000,52.000,52.000,52.000,53.000,54.000,54.000,57.000,56.000,57.000,55.000,53.000,48.000,48.000,55.000,42.000,46.000,39.000,38.000,46.000,43.000,45.000,45.000,48.000,50.000,54.000,53.000,59.000,55.000,60.000,61.000,70.000,55.000,47.000,48.000,58.000,54.000,51.000,47.000,48.000,52.000,50.000,52.000,49.000,57.000,66.000,70.000,74.000,75.000,75.000,73.000,70.000,70.000,70.000,71.000,70.000,70.000,73.000,76.000,75.000,76.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,76.000,77.000,78.000,123.000,79.000,79.000,79.000,77.000,75.000,120.000,73.000,72.000,68.000,68.000,68.000,68.000,66.000,60.000,65.000,61.000,62.000,81.000,68.000,61.000,55.000,59.000,75.000,80.000}
-64.359 DESIRED_THRUST iJoystick 85.5708487197
-64.359 DESIRED_RUDDER iJoystick 0
-64.375 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.3712,20.3162,-0.9424},Vel=[3x1]{-0.8174,-0.5940,2.0513},Raw=[2x1]{22.7880,-0.9424},time=1225719876.02252435684204,Speed=1.01048450687772,Pitch=0.03813701347526,Roll=0.02243353733839,PitchDot=0.00897341493535,RollDot=0.00085247441886
-64.375 ODOMETRY_POSE iPlatform Pose=[3x1]{6.3712,20.3162,-0.9421},Vel=[3x1]{-0.8174,-0.5940,2.0513},Raw=[2x1]{22.7880,-0.9424},time=1225719876.0225,Speed=1.0105,Pitch=0.0043,Roll=0.0440,PitchDot=-0.0034,RollDot=-0.0084
-64.354 LMS_LASER_2D_RIGHT LMS2 ID=4104,time=1225719876.001390,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=193,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.016,13.753,11.622,10.276,9.300,8.457,7.651,6.988,6.450,5.972,5.588,5.284,4.936,4.671,4.411,4.139,3.921,3.735,3.547,3.395,3.254,3.131,2.968,2.855,2.769,2.672,2.550,2.476,2.371,2.289,2.218,2.157,2.096,2.019,1.961,1.918,1.855,1.811,1.766,1.715,1.679,1.621,1.582,1.542,1.496,1.470,1.465,1.443,1.414,1.378,1.369,1.343,1.323,1.304,1.294,1.262,1.244,1.225,1.190,1.166,1.158,1.142,1.128,1.126,1.117,1.114,1.138,1.131,1.146,1.145,1.145,1.131,1.133,1.119,1.136,1.131,1.120,1.110,1.064,1.041,1.032,1.024,1.015,1.009,0.989,0.982,0.981,0.976,0.979},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,85.000,126.000,93.000,71.000,59.000,56.000,55.000,57.000,65.000,67.000,69.000,69.000,70.000,70.000,72.000,75.000,74.000,77.000,76.000,78.000,78.000,80.000,81.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,75.000,74.000,75.000,80.000,80.000,78.000,77.000,77.000,71.000,72.000,74.000,72.000,70.000,68.000,74.000,73.000,69.000,69.000,70.000,72.000,72.000,75.000,76.000,74.000,68.000,59.000,53.000,45.000,42.000,35.000,31.000,30.000,30.000,35.000,40.000,44.000,39.000,29.000,26.000,26.000,26.000,27.000,26.000,26.000,31.000,36.000,35.000,37.000}
-64.354 LMS_LASER_2D_LEFT LMS1 ID=4231,time=1225719875.995900,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=228,Range=[181]{1.029,1.044,1.054,1.061,1.057,1.062,1.073,1.070,1.098,1.102,1.097,1.116,1.147,1.158,1.167,1.178,1.187,1.208,1.216,1.224,1.242,1.252,1.269,1.281,1.293,1.311,1.327,1.346,1.360,1.376,1.396,1.419,1.433,1.459,1.477,1.499,1.530,1.555,1.573,1.601,1.632,1.654,1.671,1.686,1.722,1.780,1.822,1.848,1.878,1.935,1.975,2.017,2.064,2.105,2.160,2.206,2.265,2.318,2.386,2.450,2.505,2.569,2.595,2.588,2.658,2.734,2.807,2.888,2.935,3.012,3.115,3.224,3.368,3.475,3.593,3.739,3.903,3.921,3.902,3.892,3.902,3.941,3.961,3.971,3.974,3.974,3.980,3.981,3.976,3.996,4.041,4.076,4.067,4.076,4.106,4.112,4.111,4.109,4.109,4.110,4.123,4.114,4.119,4.127,4.129,4.129,4.138,4.148,4.150,4.159,4.161,4.167,4.173,4.179,4.189,4.197,4.205,4.216,4.229,4.239,4.251,4.252,4.269,4.278,4.295,4.305,4.321,4.338,4.352,4.364,4.373,4.391,4.400,4.416,4.433,4.452,4.473,4.485,4.501,4.518,4.545,4.563,4.579,4.594,4.611,4.637,4.654,4.681,4.706,4.739,4.760,4.775,4.806,4.830,4.855,4.883,3.133,2.981,2.930,2.927,2.940,2.950,3.093,5.130,5.164,5.210,5.241,5.288,5.303,5.337,5.398,5.392,5.445,5.454,4.833,4.728,4.733,4.783,4.939,4.955,4.733},Reflectance=[181]{35.000,40.000,40.000,40.000,47.000,46.000,42.000,31.000,33.000,32.000,30.000,32.000,41.000,42.000,47.000,44.000,49.000,45.000,45.000,50.000,46.000,51.000,51.000,48.000,49.000,53.000,49.000,50.000,48.000,51.000,52.000,51.000,49.000,50.000,53.000,52.000,54.000,53.000,54.000,51.000,53.000,55.000,58.000,62.000,56.000,47.000,45.000,54.000,55.000,46.000,48.000,43.000,41.000,34.000,42.000,48.000,44.000,46.000,49.000,50.000,55.000,56.000,55.000,60.000,59.000,69.000,53.000,48.000,46.000,58.000,57.000,54.000,48.000,47.000,51.000,56.000,50.000,49.000,60.000,68.000,71.000,74.000,75.000,75.000,74.000,71.000,71.000,69.000,72.000,71.000,71.000,73.000,75.000,75.000,77.000,78.000,78.000,77.000,77.000,78.000,79.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,76.000,76.000,77.000,77.000,77.000,77.000,125.000,86.000,79.000,78.000,77.000,75.000,115.000,71.000,73.000,69.000,67.000,68.000,67.000,65.000,59.000,64.000,62.000,62.000,77.000,67.000,64.000,53.000,65.000,73.000,63.000}
-64.367 LMS_LASER_2D_RIGHT LMS2 ID=4105,time=1225719876.014726,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=194,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.213,26.372,16.895,13.556,11.436,10.185,9.239,8.403,7.599,6.978,6.450,5.989,5.596,5.246,4.917,4.646,4.394,4.130,3.897,3.741,3.521,3.394,3.229,3.115,2.976,2.852,2.749,2.670,2.541,2.457,2.352,2.281,2.219,2.157,2.079,2.000,1.961,1.918,1.855,1.801,1.757,1.714,1.677,1.616,1.572,1.536,1.494,1.477,1.456,1.440,1.400,1.378,1.373,1.342,1.324,1.300,1.286,1.263,1.243,1.225,1.198,1.182,1.158,1.141,1.126,1.117,1.116,1.113,1.123,1.132,1.139,1.144,1.139,1.141,1.133,1.129,1.136,1.125,1.119,1.099,1.089,1.040,1.035,1.022,1.022,0.997,0.990,0.968,0.972,0.969,0.976},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,1.000,7.000,90.000,126.000,92.000,69.000,59.000,56.000,55.000,57.000,65.000,65.000,68.000,69.000,69.000,71.000,71.000,75.000,75.000,77.000,77.000,78.000,79.000,80.000,81.000,79.000,80.000,80.000,80.000,80.000,77.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,78.000,78.000,71.000,74.000,74.000,80.000,74.000,72.000,76.000,78.000,76.000,75.000,73.000,74.000,75.000,75.000,74.000,71.000,70.000,69.000,70.000,72.000,72.000,74.000,74.000,72.000,66.000,60.000,53.000,45.000,39.000,34.000,34.000,31.000,31.000,36.000,41.000,36.000,34.000,32.000,27.000,26.000,26.000,26.000,26.000,26.000,29.000,34.000,33.000,36.000}
-64.367 LMS_LASER_2D_LEFT LMS1 ID=4232,time=1225719876.009242,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=229,Range=[181]{1.038,1.037,1.045,1.060,1.067,1.068,1.062,1.092,1.106,1.113,1.116,1.132,1.138,1.156,1.166,1.174,1.187,1.197,1.213,1.232,1.250,1.252,1.269,1.284,1.291,1.312,1.331,1.352,1.364,1.389,1.401,1.416,1.436,1.455,1.477,1.503,1.520,1.565,1.589,1.609,1.631,1.662,1.677,1.686,1.742,1.790,1.827,1.844,1.876,1.938,1.974,2.022,2.064,2.113,2.172,2.214,2.277,2.329,2.385,2.464,2.492,2.569,2.579,2.597,2.679,2.744,2.825,2.904,2.944,3.033,3.144,3.244,3.371,3.473,3.595,3.746,3.936,3.927,3.904,3.892,3.899,3.942,3.962,3.970,3.973,3.971,3.981,3.986,3.978,3.998,4.044,4.070,4.077,4.085,4.108,4.102,4.112,4.110,4.111,4.119,4.120,4.122,4.119,4.129,4.130,4.137,4.138,4.138,4.149,4.158,4.158,4.166,4.173,4.183,4.191,4.195,4.203,4.215,4.229,4.238,4.250,4.252,4.267,4.277,4.295,4.306,4.322,4.340,4.353,4.364,4.373,4.391,4.399,4.417,4.440,4.452,4.473,4.483,4.501,4.529,4.543,4.555,4.576,4.594,4.619,4.638,4.664,4.690,4.708,4.739,4.760,4.776,4.812,4.832,4.855,4.884,2.994,3.001,2.930,2.927,2.939,2.949,3.059,5.131,5.163,5.214,5.247,5.290,5.309,5.347,5.399,5.392,5.445,5.445,4.837,4.767,4.708,4.727,5.259,5.229,4.747},Reflectance=[181]{38.000,40.000,40.000,40.000,43.000,39.000,30.000,33.000,34.000,34.000,32.000,35.000,46.000,45.000,46.000,46.000,52.000,49.000,49.000,49.000,45.000,47.000,47.000,53.000,52.000,50.000,47.000,48.000,50.000,52.000,54.000,50.000,51.000,52.000,50.000,53.000,53.000,54.000,53.000,51.000,52.000,54.000,61.000,62.000,54.000,48.000,44.000,56.000,54.000,47.000,48.000,42.000,46.000,41.000,39.000,42.000,42.000,51.000,48.000,49.000,61.000,56.000,56.000,60.000,55.000,61.000,54.000,47.000,46.000,55.000,58.000,52.000,49.000,50.000,52.000,55.000,49.000,48.000,61.000,68.000,70.000,74.000,75.000,75.000,74.000,73.000,71.000,70.000,72.000,71.000,72.000,74.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,76.000,76.000,77.000,77.000,77.000,77.000,45.000,94.000,79.000,79.000,77.000,75.000,107.000,71.000,73.000,67.000,66.000,68.000,66.000,63.000,60.000,64.000,63.000,63.000,78.000,64.000,62.000,41.000,58.000,66.000,68.000}
-64.383 DESIRED_THRUST iJoystick 85.5708487197
-64.383 DESIRED_RUDDER iJoystick 0
-64.379 LMS_LASER_2D_RIGHT LMS2 ID=4106,time=1225719876.028062,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=195,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.254,-1.000,16.784,13.486,11.375,10.157,9.212,8.359,7.570,6.944,6.417,5.963,5.569,5.228,4.917,4.629,4.375,4.108,3.902,3.733,3.540,3.366,3.231,3.103,2.969,2.844,2.736,2.653,2.550,2.451,2.353,2.283,2.210,2.147,2.070,2.000,1.961,1.908,1.838,1.793,1.739,1.722,1.654,1.607,1.574,1.538,1.498,1.472,1.447,1.426,1.402,1.379,1.360,1.333,1.328,1.311,1.286,1.264,1.250,1.233,1.207,1.182,1.158,1.134,1.126,1.109,1.117,1.113,1.127,1.133,1.140,1.137,1.133,1.131,1.119,1.113,1.129,1.129,1.075,1.103,1.098,1.082,1.034,1.023,1.009,1.005,0.989,0.962,0.973,0.972,0.972},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,1.000,0.000,94.000,126.000,92.000,67.000,58.000,56.000,54.000,58.000,64.000,66.000,68.000,68.000,69.000,70.000,72.000,73.000,74.000,76.000,77.000,77.000,80.000,79.000,81.000,79.000,79.000,80.000,80.000,80.000,78.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,74.000,74.000,75.000,74.000,75.000,68.000,71.000,75.000,75.000,74.000,76.000,74.000,75.000,75.000,76.000,74.000,69.000,68.000,68.000,70.000,71.000,73.000,77.000,77.000,72.000,67.000,58.000,53.000,46.000,37.000,31.000,31.000,30.000,29.000,33.000,35.000,28.000,39.000,46.000,38.000,27.000,27.000,27.000,27.000,26.000,29.000,34.000,34.000,38.000}
-64.379 LMS_LASER_2D_LEFT LMS1 ID=4233,time=1225719876.022583,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=230,Range=[181]{1.039,1.043,1.055,1.061,1.067,1.078,1.085,1.102,1.095,1.112,1.132,1.136,1.150,1.158,1.166,1.177,1.191,1.202,1.212,1.226,1.237,1.256,1.277,1.287,1.298,1.319,1.331,1.347,1.370,1.387,1.396,1.416,1.441,1.459,1.486,1.516,1.530,1.565,1.574,1.614,1.642,1.670,1.659,1.686,1.742,1.791,1.827,1.840,1.883,1.945,1.986,2.017,2.063,2.122,2.158,2.226,2.279,2.331,2.395,2.471,2.516,2.590,2.581,2.590,2.688,2.759,2.828,2.895,2.955,3.028,3.146,3.295,3.373,3.475,3.598,3.756,3.929,3.924,3.911,3.891,3.901,3.950,3.962,3.975,3.974,3.971,3.991,3.987,3.978,4.002,4.042,4.076,4.070,4.082,4.100,4.103,4.109,4.109,4.109,4.119,4.120,4.122,4.120,4.129,4.140,4.131,4.138,4.139,4.149,4.158,4.158,4.165,4.174,4.180,4.188,4.195,4.205,4.215,4.228,4.239,4.241,4.259,4.268,4.286,4.295,4.306,4.321,4.336,4.352,4.364,4.373,4.392,4.401,4.416,4.431,4.453,4.473,4.489,4.500,4.527,4.543,4.556,4.577,4.594,4.621,4.637,4.663,4.681,4.707,4.739,4.753,4.777,4.805,4.834,4.867,4.889,3.002,3.021,2.928,2.928,2.935,2.942,3.044,2.992,5.168,5.211,5.247,5.284,5.310,5.355,5.392,5.392,5.445,5.445,4.844,4.750,4.664,4.752,5.337,4.968,4.766},Reflectance=[181]{42.000,39.000,38.000,40.000,43.000,40.000,40.000,39.000,33.000,33.000,42.000,44.000,42.000,42.000,46.000,48.000,46.000,48.000,48.000,47.000,48.000,44.000,45.000,47.000,48.000,46.000,51.000,50.000,48.000,48.000,52.000,53.000,53.000,53.000,50.000,52.000,54.000,54.000,54.000,53.000,50.000,54.000,66.000,62.000,54.000,48.000,49.000,58.000,53.000,45.000,45.000,48.000,46.000,40.000,46.000,39.000,43.000,52.000,44.000,48.000,60.000,53.000,62.000,62.000,52.000,56.000,55.000,51.000,48.000,49.000,47.000,47.000,46.000,56.000,57.000,56.000,49.000,47.000,60.000,67.000,70.000,74.000,75.000,74.000,74.000,73.000,71.000,70.000,72.000,70.000,71.000,73.000,76.000,75.000,77.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,78.000,77.000,78.000,78.000,77.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,23.000,104.000,79.000,79.000,78.000,76.000,101.000,26.000,72.000,66.000,65.000,67.000,65.000,62.000,62.000,63.000,64.000,63.000,80.000,66.000,64.000,44.000,53.000,72.000,71.000}
-64.390 LMS_LASER_2D_LEFT LMS1 ID=4234,time=1225719876.035921,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=231,Range=[181]{1.036,1.044,1.043,1.056,1.061,1.074,1.080,1.099,1.109,1.118,1.128,1.138,1.139,1.164,1.166,1.178,1.198,1.206,1.219,1.236,1.256,1.258,1.260,1.290,1.293,1.318,1.331,1.346,1.370,1.386,1.407,1.415,1.434,1.459,1.481,1.512,1.538,1.562,1.580,1.600,1.642,1.659,1.659,1.705,1.740,1.788,1.826,1.840,1.881,1.939,1.976,2.022,2.064,2.120,2.162,2.224,2.281,2.325,2.407,2.475,2.527,2.574,2.572,2.581,2.692,2.761,2.815,2.877,2.959,3.033,3.161,3.310,3.391,3.492,3.589,3.772,3.933,3.924,3.896,3.891,3.902,3.947,3.962,3.971,3.974,3.977,3.981,3.985,3.980,4.000,4.038,4.068,4.068,4.084,4.099,4.102,4.110,4.109,4.111,4.120,4.120,4.119,4.122,4.130,4.129,4.131,4.140,4.140,4.147,4.158,4.158,4.165,4.172,4.179,4.188,4.194,4.204,4.213,4.228,4.241,4.252,4.252,4.269,4.277,4.293,4.304,4.319,4.336,4.350,4.364,4.372,4.382,4.399,4.416,4.433,4.453,4.474,4.481,4.500,4.526,4.543,4.554,4.576,4.594,4.611,4.638,4.655,4.691,4.709,4.738,4.755,4.778,4.808,4.825,4.866,4.889,4.913,3.050,2.926,2.918,2.925,2.933,3.028,2.982,5.165,5.211,5.247,5.282,5.310,5.355,5.392,5.392,5.445,5.445,4.807,4.731,4.708,4.791,5.146,4.860,4.809},Reflectance=[181]{40.000,37.000,40.000,42.000,44.000,42.000,38.000,35.000,36.000,43.000,44.000,40.000,46.000,40.000,45.000,44.000,41.000,46.000,48.000,43.000,44.000,46.000,47.000,43.000,46.000,49.000,51.000,53.000,52.000,47.000,53.000,53.000,54.000,53.000,52.000,50.000,54.000,52.000,57.000,55.000,53.000,57.000,64.000,57.000,53.000,55.000,52.000,58.000,52.000,43.000,49.000,45.000,45.000,40.000,48.000,43.000,49.000,53.000,42.000,46.000,64.000,58.000,64.000,64.000,50.000,49.000,61.000,54.000,50.000,48.000,50.000,46.000,46.000,55.000,57.000,55.000,51.000,47.000,63.000,67.000,71.000,73.000,75.000,75.000,74.000,72.000,71.000,70.000,73.000,69.000,70.000,73.000,76.000,75.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,76.000,114.000,78.000,79.000,78.000,75.000,95.000,39.000,71.000,65.000,64.000,66.000,62.000,63.000,61.000,62.000,64.000,63.000,81.000,68.000,57.000,49.000,52.000,73.000,61.000}
-64.402 LMS_LASER_2D_RIGHT LMS2 ID=4107,time=1225719876.041407,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=196,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.306,26.448,16.857,13.539,11.392,10.185,9.214,8.411,7.615,6.962,6.383,5.955,5.553,5.237,4.917,4.614,4.357,4.117,3.911,3.741,3.549,3.374,3.230,3.103,2.975,2.848,2.757,2.642,2.541,2.453,2.358,2.283,2.211,2.147,2.076,2.008,1.954,1.901,1.837,1.778,1.758,1.699,1.643,1.627,1.581,1.545,1.510,1.464,1.445,1.425,1.404,1.375,1.359,1.350,1.322,1.302,1.290,1.278,1.247,1.213,1.198,1.173,1.157,1.133,1.121,1.117,1.107,1.115,1.125,1.138,1.146,1.141,1.138,1.129,1.130,1.122,1.098,1.090,1.074,1.104,1.092,1.084,1.075,1.028,1.015,1.003,0.989,0.973,0.978,0.968,0.973},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,2.000,2.000,92.000,127.000,92.000,69.000,60.000,56.000,54.000,58.000,65.000,66.000,68.000,68.000,69.000,71.000,72.000,73.000,73.000,76.000,77.000,77.000,79.000,79.000,80.000,80.000,79.000,80.000,80.000,81.000,79.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,77.000,79.000,77.000,72.000,77.000,77.000,74.000,74.000,69.000,67.000,74.000,76.000,75.000,76.000,72.000,70.000,75.000,74.000,69.000,63.000,66.000,68.000,68.000,69.000,72.000,75.000,77.000,72.000,69.000,57.000,48.000,45.000,41.000,37.000,31.000,30.000,30.000,27.000,27.000,27.000,33.000,50.000,51.000,36.000,27.000,27.000,27.000,27.000,28.000,34.000,35.000,38.000}
-64.407 DESIRED_THRUST iJoystick 86.60237434
-64.407 DESIRED_RUDDER iJoystick 0
-64.411 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.4035,20.3398,-0.9411},Vel=[3x1]{-0.8108,-0.5908,0.7692},Raw=[2x1]{22.8280,-0.9411},time=1225719876.05847549438477,Speed=1.00318331824421,Pitch=0.03813701347526,Roll=0.02467689107222,PitchDot=-0.00897341493535,RollDot=-0.00017946829871
-64.411 ODOMETRY_POSE iPlatform Pose=[3x1]{6.4035,20.3398,-0.9407},Vel=[3x1]{-0.8108,-0.5908,0.7692},Raw=[2x1]{22.8280,-0.9411},time=1225719876.0585,Speed=1.0032,Pitch=0.0025,Roll=0.0454,PitchDot=-0.0066,RollDot=0.0061
-64.402 LMS_LASER_2D_LEFT LMS1 ID=4235,time=1225719876.049258,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=232,Range=[181]{1.031,1.040,1.053,1.063,1.068,1.073,1.083,1.094,1.109,1.118,1.124,1.132,1.148,1.162,1.175,1.183,1.189,1.210,1.225,1.231,1.254,1.264,1.276,1.281,1.301,1.319,1.337,1.350,1.369,1.384,1.408,1.418,1.441,1.468,1.488,1.512,1.546,1.560,1.577,1.603,1.642,1.650,1.659,1.707,1.755,1.785,1.821,1.852,1.902,1.938,1.979,2.022,2.072,2.118,2.162,2.211,2.279,2.318,2.404,2.477,2.539,2.563,2.572,2.590,2.679,2.757,2.823,2.869,2.960,3.028,3.157,3.313,3.410,3.491,3.590,3.750,3.928,3.926,3.896,3.896,3.910,3.949,3.962,3.970,3.966,3.967,3.980,3.983,3.978,3.996,4.041,4.064,4.070,4.076,4.109,4.111,4.111,4.110,4.108,4.116,4.118,4.122,4.121,4.121,4.129,4.129,4.139,4.140,4.148,4.157,4.161,4.164,4.171,4.180,4.188,4.193,4.203,4.211,4.226,4.240,4.241,4.252,4.270,4.278,4.293,4.304,4.318,4.335,4.343,4.354,4.372,4.392,4.399,4.416,4.434,4.452,4.472,4.490,4.508,4.518,4.543,4.564,4.575,4.594,4.612,4.638,4.654,4.681,4.707,4.740,4.755,4.779,4.806,4.833,4.857,4.882,4.915,3.090,2.932,2.918,2.916,2.925,2.938,2.963,5.153,5.201,5.238,5.283,5.310,5.355,5.392,5.392,5.445,5.428,4.803,4.728,4.772,4.897,4.899,4.795,4.862},Reflectance=[181]{35.000,38.000,37.000,37.000,39.000,42.000,42.000,40.000,38.000,43.000,42.000,42.000,45.000,44.000,42.000,42.000,46.000,43.000,45.000,46.000,39.000,39.000,46.000,48.000,46.000,46.000,50.000,51.000,48.000,50.000,53.000,51.000,53.000,53.000,51.000,50.000,49.000,48.000,59.000,56.000,53.000,61.000,63.000,54.000,52.000,53.000,50.000,55.000,45.000,47.000,45.000,42.000,41.000,43.000,48.000,46.000,52.000,54.000,44.000,42.000,58.000,62.000,65.000,64.000,55.000,47.000,57.000,54.000,50.000,49.000,52.000,47.000,54.000,54.000,58.000,58.000,49.000,48.000,63.000,66.000,70.000,74.000,75.000,75.000,74.000,72.000,71.000,69.000,72.000,71.000,71.000,72.000,76.000,75.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,77.000,77.000,77.000,76.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,120.000,78.000,78.000,78.000,76.000,75.000,55.000,70.000,64.000,65.000,63.000,61.000,62.000,61.000,61.000,64.000,63.000,80.000,70.000,60.000,54.000,55.000,67.000,50.000}
-64.415 LMS_LASER_2D_RIGHT LMS2 ID=4108,time=1225719876.054751,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=197,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.428,16.909,13.575,11.429,10.195,9.249,8.429,7.642,6.988,6.442,5.981,5.596,5.255,4.935,4.629,4.348,4.134,3.919,3.748,3.541,3.386,3.249,3.113,2.966,2.855,2.760,2.650,2.532,2.459,2.369,2.291,2.210,2.147,2.095,2.010,1.961,1.915,1.844,1.793,1.765,1.688,1.639,1.622,1.583,1.554,1.530,1.474,1.437,1.422,1.393,1.379,1.370,1.349,1.330,1.305,1.289,1.268,1.239,1.205,1.191,1.174,1.157,1.132,1.122,1.115,1.107,1.113,1.118,1.129,1.129,1.148,1.141,1.129,1.121,1.113,1.120,1.098,1.071,1.068,1.098,1.084,1.073,1.066,1.022,1.016,1.011,0.973,0.978,0.966,0.976},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,2.000,89.000,127.000,92.000,70.000,59.000,56.000,54.000,57.000,64.000,66.000,67.000,68.000,69.000,70.000,72.000,73.000,74.000,76.000,77.000,78.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,76.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,72.000,69.000,72.000,76.000,77.000,77.000,70.000,69.000,72.000,73.000,68.000,65.000,66.000,69.000,70.000,70.000,70.000,67.000,69.000,72.000,67.000,62.000,55.000,52.000,45.000,46.000,33.000,29.000,29.000,32.000,28.000,27.000,26.000,38.000,51.000,50.000,38.000,29.000,28.000,30.000,28.000,34.000,33.000,36.000}
-64.415 LMS_LASER_2D_LEFT LMS1 ID=4236,time=1225719876.062595,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=233,Range=[181]{1.032,1.042,1.050,1.054,1.065,1.073,1.084,1.090,1.099,1.122,1.122,1.135,1.137,1.144,1.175,1.175,1.192,1.203,1.225,1.234,1.251,1.267,1.268,1.284,1.299,1.324,1.330,1.352,1.367,1.392,1.401,1.423,1.446,1.469,1.482,1.512,1.541,1.569,1.578,1.595,1.643,1.649,1.665,1.717,1.755,1.776,1.827,1.876,1.892,1.936,1.975,2.030,2.071,2.120,2.155,2.215,2.279,2.316,2.403,2.474,2.533,2.571,2.572,2.581,2.671,2.736,2.812,2.876,2.950,3.016,3.130,3.292,3.397,3.440,3.579,3.721,3.921,3.919,3.896,3.901,3.899,3.942,3.962,3.971,3.967,3.971,3.976,3.985,3.973,3.996,4.037,4.067,4.069,4.076,4.108,4.103,4.102,4.109,4.108,4.119,4.111,4.111,4.123,4.122,4.121,4.130,4.129,4.138,4.147,4.149,4.157,4.164,4.173,4.172,4.186,4.195,4.203,4.211,4.228,4.238,4.240,4.252,4.259,4.278,4.294,4.300,4.320,4.336,4.342,4.355,4.373,4.391,4.400,4.416,4.432,4.451,4.475,4.491,4.500,4.527,4.543,4.562,4.576,4.594,4.602,4.637,4.655,4.680,4.698,4.732,4.758,4.778,4.796,4.831,4.849,4.881,4.913,2.975,3.005,2.910,2.910,2.918,2.933,2.935,5.149,5.193,5.229,5.265,5.308,5.347,5.389,5.392,5.437,5.445,4.812,4.751,4.872,5.011,4.904,4.775,4.822},Reflectance=[181]{42.000,38.000,36.000,35.000,42.000,42.000,43.000,42.000,47.000,41.000,41.000,39.000,44.000,43.000,42.000,42.000,47.000,43.000,42.000,42.000,42.000,41.000,46.000,49.000,44.000,43.000,46.000,48.000,47.000,46.000,54.000,53.000,51.000,50.000,52.000,54.000,47.000,52.000,60.000,55.000,54.000,61.000,60.000,54.000,52.000,53.000,49.000,45.000,46.000,50.000,44.000,41.000,41.000,40.000,49.000,43.000,39.000,46.000,40.000,41.000,60.000,61.000,64.000,65.000,56.000,53.000,52.000,50.000,53.000,48.000,52.000,53.000,62.000,60.000,56.000,60.000,53.000,49.000,62.000,59.000,70.000,74.000,75.000,75.000,74.000,73.000,72.000,70.000,71.000,71.000,72.000,73.000,76.000,75.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,32.000,98.000,78.000,78.000,76.000,75.000,64.000,66.000,65.000,65.000,63.000,60.000,61.000,59.000,61.000,64.000,63.000,81.000,69.000,72.000,66.000,64.000,50.000,58.000}
-64.426 LMS_LASER_2D_RIGHT LMS2 ID=4109,time=1225719876.068094,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=198,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.413,17.052,13.754,11.584,10.321,9.321,8.509,7.721,6.992,6.467,5.990,5.621,5.273,4.954,4.654,4.376,4.151,3.932,3.750,3.586,3.396,3.248,3.090,2.967,2.880,2.760,2.658,2.550,2.450,2.372,2.291,2.228,2.148,2.086,2.019,1.975,1.924,1.863,1.807,1.773,1.732,1.688,1.637,1.598,1.558,1.533,1.511,1.457,1.423,1.411,1.382,1.363,1.342,1.323,1.305,1.294,1.278,1.241,1.207,1.200,1.175,1.157,1.141,1.123,1.128,1.114,1.115,1.120,1.127,1.133,1.144,1.137,1.133,1.129,1.119,1.118,1.092,1.080,1.065,1.057,1.084,1.072,1.055,1.052,1.044,1.036,1.019,0.995,0.947,0.951},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,2.000,88.000,129.000,96.000,72.000,60.000,55.000,54.000,59.000,64.000,66.000,67.000,68.000,70.000,70.000,73.000,74.000,75.000,77.000,77.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,78.000,79.000,76.000,77.000,77.000,78.000,78.000,77.000,74.000,73.000,75.000,78.000,77.000,74.000,71.000,72.000,68.000,69.000,68.000,68.000,72.000,72.000,70.000,71.000,69.000,63.000,69.000,69.000,65.000,58.000,47.000,43.000,40.000,34.000,32.000,30.000,31.000,28.000,27.000,27.000,27.000,33.000,49.000,52.000,51.000,44.000,45.000,37.000,35.000,27.000,28.000}
-64.431 DESIRED_THRUST iJoystick 86.60237434
-64.431 DESIRED_RUDDER iJoystick 0
-64.438 LMS_LASER_2D_RIGHT LMS2 ID=4110,time=1225719876.081435,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=199,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.464,17.387,14.395,11.619,10.431,9.444,8.623,7.794,7.039,6.580,6.043,5.697,5.318,4.990,4.698,4.429,4.194,3.970,3.758,3.605,3.426,3.253,3.130,2.988,2.883,2.749,2.660,2.551,2.451,2.382,2.301,2.237,2.166,2.103,2.033,1.974,1.920,1.867,1.809,1.776,1.746,1.701,1.653,1.604,1.571,1.541,1.517,1.467,1.430,1.399,1.382,1.364,1.339,1.319,1.306,1.294,1.270,1.252,1.224,1.208,1.176,1.159,1.141,1.124,1.117,1.109,1.107,1.114,1.125,1.128,1.128,1.129,1.138,1.139,1.126,1.110,1.089,1.083,1.074,1.072,1.048,1.078,1.054,1.043,1.040,1.038,1.021,0.980,0.969,0.973},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,15.000,77.000,119.000,108.000,75.000,59.000,55.000,55.000,60.000,63.000,67.000,66.000,69.000,69.000,70.000,72.000,72.000,75.000,76.000,77.000,78.000,78.000,79.000,79.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,77.000,76.000,76.000,76.000,78.000,78.000,74.000,72.000,75.000,78.000,78.000,76.000,75.000,74.000,69.000,72.000,72.000,68.000,69.000,73.000,73.000,72.000,72.000,73.000,74.000,72.000,68.000,61.000,55.000,55.000,48.000,35.000,34.000,33.000,29.000,28.000,28.000,27.000,28.000,26.000,37.000,52.000,55.000,53.000,45.000,40.000,31.000,33.000,38.000}
-64.447 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.4273,20.3571,-0.9411},Vel=[3x1]{-0.7860,-0.5727,0.8974},Raw=[2x1]{22.8574,-0.9411},time=1225719876.09455752372742,Speed=0.97251832598347,Pitch=0.03813701347526,Roll=0.02467689107222,PitchDot=-0.02019018360455,RollDot=-0.00042623720943
-64.447 ODOMETRY_POSE iPlatform Pose=[3x1]{6.4273,20.3571,-0.9407},Vel=[3x1]{-0.7860,-0.5727,0.8975},Raw=[2x1]{22.8574,-0.9411},time=1225719876.0946,Speed=0.9725,Pitch=0.0025,Roll=0.0454,PitchDot=-0.0129,RollDot=0.0155
-64.455 DESIRED_THRUST iJoystick 86.60237434
-64.455 DESIRED_RUDDER iJoystick 0
-64.427 LMS_LASER_2D_LEFT LMS1 ID=4237,time=1225719876.075931,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=234,Range=[181]{1.026,1.038,1.041,1.058,1.063,1.069,1.084,1.091,1.098,1.112,1.113,1.134,1.141,1.160,1.170,1.181,1.190,1.200,1.222,1.238,1.248,1.265,1.271,1.280,1.301,1.317,1.334,1.343,1.366,1.392,1.403,1.418,1.447,1.453,1.479,1.504,1.540,1.566,1.572,1.606,1.637,1.648,1.663,1.717,1.751,1.793,1.812,1.855,1.874,1.928,1.973,2.018,2.061,2.109,2.164,2.212,2.275,2.337,2.393,2.465,2.535,2.554,2.579,2.581,2.663,2.736,2.804,2.868,2.942,3.016,3.108,3.259,3.397,3.415,3.563,3.738,3.910,3.916,3.905,3.903,3.897,3.942,3.954,3.971,3.967,3.974,3.970,3.986,3.967,3.990,4.030,4.055,4.068,4.068,4.099,4.103,4.102,4.110,4.109,4.111,4.112,4.112,4.113,4.122,4.122,4.130,4.129,4.140,4.148,4.148,4.156,4.165,4.172,4.171,4.180,4.193,4.194,4.204,4.220,4.230,4.239,4.251,4.259,4.278,4.286,4.292,4.319,4.326,4.343,4.355,4.364,4.382,4.400,4.408,4.432,4.443,4.462,4.486,4.493,4.518,4.537,4.547,4.576,4.585,4.602,4.628,4.655,4.672,4.699,4.723,4.748,4.772,4.795,4.822,4.849,4.881,4.913,4.936,3.051,2.917,2.902,2.906,2.916,3.013,2.957,5.181,5.214,5.256,5.308,5.344,5.380,5.392,5.419,5.445,4.833,4.767,4.923,5.265,4.810,4.711,4.708},Reflectance=[181]{37.000,37.000,43.000,43.000,41.000,44.000,43.000,47.000,45.000,44.000,46.000,43.000,42.000,38.000,44.000,40.000,45.000,47.000,44.000,39.000,40.000,40.000,43.000,48.000,49.000,49.000,52.000,48.000,45.000,45.000,51.000,51.000,48.000,51.000,51.000,54.000,47.000,54.000,57.000,53.000,51.000,60.000,59.000,54.000,54.000,53.000,50.000,52.000,57.000,45.000,43.000,44.000,44.000,43.000,44.000,45.000,41.000,42.000,43.000,44.000,56.000,62.000,60.000,64.000,56.000,53.000,49.000,46.000,50.000,48.000,50.000,54.000,61.000,71.000,46.000,59.000,52.000,48.000,58.000,56.000,67.000,74.000,75.000,75.000,74.000,74.000,70.000,70.000,72.000,71.000,70.000,72.000,76.000,76.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,115.000,78.000,79.000,77.000,75.000,96.000,38.000,68.000,67.000,64.000,60.000,60.000,60.000,63.000,65.000,65.000,83.000,65.000,72.000,62.000,50.000,51.000,71.000}
-64.450 LMS_LASER_2D_RIGHT LMS2 ID=4111,time=1225719876.094774,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=200,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.355,17.790,14.935,12.229,10.606,9.562,8.733,7.888,7.083,6.623,6.089,5.723,5.380,5.041,4.732,4.456,4.221,4.001,3.787,3.614,3.461,3.298,3.162,3.008,2.898,2.795,2.678,2.571,2.477,2.371,2.309,2.246,2.175,2.111,2.049,1.979,1.923,1.850,1.821,1.788,1.758,1.713,1.661,1.623,1.573,1.541,1.526,1.474,1.431,1.404,1.377,1.365,1.341,1.321,1.305,1.294,1.262,1.253,1.242,1.198,1.174,1.158,1.140,1.133,1.117,1.111,1.109,1.114,1.127,1.130,1.136,1.133,1.141,1.132,1.127,1.119,1.104,1.117,1.072,1.060,1.049,1.048,1.067,1.048,1.034,1.031,1.017,0.997,0.966,0.978},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,9.000,105.000,109.000,104.000,78.000,61.000,56.000,56.000,58.000,62.000,67.000,66.000,68.000,70.000,70.000,72.000,73.000,74.000,78.000,78.000,78.000,78.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,77.000,75.000,79.000,80.000,79.000,78.000,76.000,76.000,77.000,78.000,79.000,76.000,73.000,72.000,76.000,75.000,76.000,75.000,72.000,68.000,74.000,73.000,71.000,69.000,69.000,72.000,70.000,71.000,74.000,77.000,74.000,69.000,62.000,52.000,51.000,50.000,42.000,32.000,31.000,30.000,29.000,36.000,28.000,27.000,26.000,26.000,43.000,53.000,54.000,50.000,47.000,36.000,32.000,37.000}
-64.450 LMS_LASER_2D_LEFT LMS1 ID=4238,time=1225719876.089275,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=235,Range=[181]{1.031,1.029,1.055,1.053,1.065,1.073,1.078,1.092,1.100,1.108,1.120,1.127,1.149,1.161,1.174,1.187,1.193,1.210,1.219,1.233,1.244,1.252,1.276,1.291,1.285,1.289,1.312,1.344,1.366,1.389,1.395,1.408,1.435,1.456,1.476,1.507,1.534,1.564,1.568,1.597,1.641,1.661,1.658,1.714,1.748,1.783,1.813,1.855,1.885,1.910,1.971,2.004,2.056,2.096,2.161,2.206,2.259,2.323,2.382,2.449,2.537,2.570,2.579,2.572,2.652,2.746,2.800,2.860,2.936,3.005,3.082,3.257,3.379,3.420,3.498,3.689,3.910,3.916,3.913,3.912,3.896,3.932,3.954,3.964,3.967,3.964,3.974,3.983,3.964,3.983,4.023,4.057,4.068,4.058,4.097,4.095,4.104,4.101,4.101,4.111,4.111,4.112,4.114,4.112,4.122,4.121,4.130,4.127,4.137,4.146,4.148,4.155,4.165,4.175,4.178,4.192,4.194,4.203,4.218,4.235,4.237,4.252,4.251,4.269,4.276,4.291,4.309,4.333,4.342,4.354,4.364,4.381,4.393,4.406,4.423,4.431,4.461,4.477,4.493,4.510,4.528,4.545,4.567,4.586,4.602,4.620,4.644,4.672,4.691,4.723,4.740,4.769,4.788,4.823,4.842,4.873,4.905,4.930,2.969,2.974,2.894,2.891,2.893,2.904,2.920,5.170,5.211,5.247,5.292,5.335,5.373,5.378,5.406,5.444,4.862,4.803,5.347,5.377,4.757,4.717,4.741},Reflectance=[181]{38.000,37.000,37.000,40.000,42.000,42.000,44.000,38.000,38.000,42.000,44.000,39.000,42.000,40.000,42.000,36.000,43.000,43.000,38.000,45.000,38.000,35.000,37.000,44.000,54.000,56.000,54.000,49.000,45.000,40.000,48.000,53.000,50.000,52.000,49.000,52.000,48.000,53.000,59.000,53.000,53.000,54.000,61.000,53.000,53.000,49.000,50.000,52.000,54.000,50.000,42.000,50.000,45.000,46.000,42.000,43.000,47.000,44.000,47.000,46.000,53.000,60.000,60.000,64.000,56.000,46.000,47.000,47.000,47.000,48.000,46.000,53.000,61.000,70.000,53.000,49.000,49.000,48.000,57.000,57.000,66.000,74.000,75.000,76.000,74.000,73.000,71.000,69.000,71.000,72.000,71.000,72.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,76.000,77.000,78.000,78.000,79.000,78.000,77.000,77.000,76.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,76.000,77.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,46.000,93.000,79.000,78.000,76.000,75.000,58.000,70.000,69.000,65.000,61.000,60.000,61.000,68.000,70.000,71.000,79.000,72.000,64.000,70.000,38.000,54.000,63.000}
-64.463 LMS_LASER_2D_RIGHT LMS2 ID=4112,time=1225719876.108114,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=201,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.519,18.633,15.365,12.451,10.748,9.655,8.797,7.960,7.230,6.691,6.173,5.794,5.433,5.085,4.782,4.491,4.273,4.009,3.783,3.652,3.476,3.311,3.178,3.044,2.915,2.814,2.687,2.579,2.479,2.398,2.320,2.255,2.202,2.121,2.053,1.991,1.942,1.866,1.829,1.788,1.759,1.725,1.672,1.628,1.584,1.545,1.519,1.475,1.430,1.404,1.378,1.360,1.341,1.329,1.296,1.278,1.261,1.251,1.242,1.207,1.173,1.172,1.147,1.124,1.110,1.109,1.108,1.105,1.124,1.125,1.135,1.137,1.136,1.142,1.135,1.110,1.093,1.121,1.092,1.060,1.048,1.048,1.034,1.059,1.044,1.041,1.021,1.010,0.977,0.968},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,43.000,24.000,104.000,113.000,81.000,62.000,56.000,56.000,58.000,60.000,66.000,66.000,68.000,69.000,70.000,71.000,72.000,74.000,79.000,78.000,77.000,77.000,79.000,80.000,80.000,81.000,80.000,81.000,81.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,77.000,79.000,80.000,79.000,79.000,77.000,77.000,78.000,76.000,77.000,74.000,72.000,72.000,72.000,74.000,72.000,75.000,72.000,70.000,71.000,71.000,70.000,69.000,69.000,67.000,67.000,72.000,74.000,76.000,76.000,69.000,61.000,50.000,47.000,45.000,36.000,36.000,33.000,29.000,28.000,37.000,31.000,27.000,26.000,26.000,26.000,43.000,51.000,47.000,49.000,44.000,33.000,35.000}
-64.463 LMS_LASER_2D_LEFT LMS1 ID=4239,time=1225719876.102620,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=236,Range=[181]{1.029,1.035,1.043,1.059,1.063,1.073,1.077,1.084,1.099,1.105,1.119,1.128,1.134,1.157,1.166,1.176,1.184,1.203,1.217,1.230,1.250,1.243,1.268,1.275,1.276,1.275,1.287,1.320,1.363,1.386,1.397,1.415,1.434,1.453,1.479,1.504,1.528,1.556,1.561,1.587,1.627,1.642,1.673,1.708,1.749,1.776,1.817,1.849,1.888,1.931,1.963,2.000,2.047,2.083,2.159,2.202,2.266,2.320,2.377,2.450,2.539,2.563,2.578,2.572,2.626,2.732,2.782,2.854,2.929,2.999,3.067,3.231,3.336,3.429,3.510,3.643,3.912,3.913,3.910,3.905,3.896,3.923,3.954,3.962,3.966,3.964,3.963,3.982,3.956,3.982,4.022,4.050,4.067,4.057,4.094,4.095,4.095,4.101,4.101,4.102,4.111,4.110,4.113,4.113,4.122,4.121,4.121,4.129,4.138,4.138,4.149,4.156,4.164,4.165,4.179,4.184,4.193,4.202,4.218,4.226,4.239,4.242,4.252,4.269,4.276,4.293,4.308,4.316,4.336,4.344,4.356,4.372,4.392,4.398,4.415,4.433,4.451,4.479,4.484,4.501,4.518,4.544,4.562,4.576,4.593,4.619,4.636,4.662,4.691,4.715,4.738,4.763,4.786,4.813,4.840,4.865,4.898,4.922,4.949,3.020,2.891,2.884,2.877,2.890,2.991,2.939,5.206,5.238,5.283,5.323,5.365,5.378,5.398,5.448,4.929,4.836,5.653,6.515,4.765,4.721,4.947},Reflectance=[181]{38.000,36.000,40.000,39.000,40.000,42.000,39.000,43.000,42.000,41.000,43.000,36.000,43.000,41.000,45.000,43.000,42.000,40.000,38.000,40.000,37.000,32.000,35.000,46.000,57.000,65.000,59.000,54.000,44.000,43.000,49.000,49.000,54.000,51.000,51.000,50.000,50.000,54.000,60.000,60.000,59.000,58.000,55.000,54.000,53.000,46.000,48.000,42.000,48.000,43.000,47.000,52.000,50.000,43.000,41.000,40.000,46.000,42.000,41.000,42.000,54.000,62.000,60.000,63.000,56.000,48.000,50.000,48.000,51.000,49.000,47.000,58.000,64.000,59.000,47.000,53.000,49.000,46.000,52.000,54.000,63.000,74.000,75.000,75.000,74.000,73.000,71.000,69.000,69.000,71.000,71.000,73.000,75.000,75.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,79.000,78.000,78.000,78.000,77.000,77.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,74.000,110.000,78.000,78.000,77.000,75.000,101.000,35.000,70.000,65.000,61.000,59.000,62.000,70.000,73.000,75.000,78.000,78.000,56.000,32.000,40.000,56.000,45.000}
-64.463 LMS_LASER_2D_LEFT LMS1 ID=4240,time=1225719876.115952,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=237,Range=[181]{1.027,1.031,1.041,1.051,1.063,1.068,1.075,1.088,1.098,1.104,1.110,1.125,1.132,1.142,1.160,1.169,1.178,1.203,1.215,1.217,1.236,1.238,1.235,1.284,1.290,1.294,1.293,1.304,1.344,1.376,1.392,1.411,1.424,1.450,1.477,1.502,1.525,1.555,1.573,1.599,1.622,1.640,1.680,1.717,1.743,1.783,1.806,1.843,1.894,1.921,1.955,1.990,2.043,2.082,2.142,2.185,2.258,2.311,2.375,2.441,2.526,2.554,2.575,2.563,2.614,2.729,2.782,2.833,2.918,3.001,3.047,3.186,3.331,3.431,3.500,3.634,3.879,3.916,3.904,3.906,3.896,3.913,3.946,3.955,3.962,3.960,3.962,3.982,3.961,3.972,4.012,4.043,4.067,4.058,4.093,4.095,4.096,4.093,4.103,4.102,4.110,4.111,4.107,4.113,4.116,4.121,4.121,4.129,4.130,4.148,4.149,4.147,4.165,4.166,4.172,4.187,4.193,4.203,4.206,4.220,4.238,4.240,4.252,4.259,4.276,4.284,4.301,4.321,4.335,4.343,4.354,4.371,4.382,4.399,4.416,4.432,4.451,4.479,4.485,4.501,4.519,4.545,4.563,4.576,4.594,4.611,4.637,4.664,4.680,4.706,4.732,4.756,4.779,4.805,4.832,4.857,4.890,4.913,4.945,3.065,2.901,2.874,2.873,2.870,2.890,2.914,5.197,5.232,5.265,4.872,5.355,5.375,5.390,5.439,4.860,5.392,5.560,5.048,4.742,4.723,4.766},Reflectance=[181]{37.000,38.000,36.000,39.000,35.000,39.000,38.000,41.000,45.000,44.000,43.000,42.000,45.000,47.000,43.000,43.000,44.000,43.000,41.000,34.000,34.000,31.000,30.000,37.000,48.000,54.000,57.000,58.000,49.000,51.000,54.000,51.000,53.000,50.000,53.000,53.000,48.000,53.000,54.000,54.000,56.000,61.000,54.000,54.000,51.000,49.000,51.000,48.000,45.000,47.000,54.000,54.000,48.000,47.000,45.000,46.000,45.000,42.000,44.000,42.000,44.000,62.000,58.000,64.000,55.000,54.000,50.000,50.000,53.000,49.000,46.000,52.000,59.000,52.000,46.000,57.000,53.000,48.000,50.000,54.000,61.000,74.000,75.000,76.000,75.000,72.000,71.000,69.000,68.000,71.000,70.000,71.000,75.000,75.000,75.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,79.000,79.000,78.000,78.000,78.000,77.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,122.000,78.000,78.000,78.000,77.000,75.000,56.000,70.000,67.000,61.000,72.000,61.000,69.000,71.000,75.000,78.000,65.000,54.000,33.000,58.000,60.000,24.000}
-64.479 DESIRED_THRUST iJoystick 86.60237434
-64.479 DESIRED_RUDDER iJoystick 0
-64.483 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.4591,20.3803,-0.9411},Vel=[3x1]{-0.7765,-0.5659,4.7436},Raw=[2x1]{22.8968,-0.9411},time=1225719876.13046741485596,Speed=0.96083642416985,Pitch=0.03589365974142,Roll=0.02243353733839,PitchDot=-0.05608384334597,RollDot=-0.00105437625490
-64.483 ODOMETRY_POSE iPlatform Pose=[3x1]{6.4591,20.3803,-0.9408},Vel=[3x1]{-0.7765,-0.5659,-1.5396},Raw=[2x1]{22.8968,-0.9411},time=1225719876.1305,Speed=0.9608,Pitch=0.0030,Roll=0.0422,PitchDot=-0.0007,RollDot=-0.0561
-63.716 CAMERA_FILE_WRITE iCameraLadybug time=1225719875.363,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.363-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.363-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.363-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.363-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.363-4.jpg
-64.474 LMS_LASER_2D_RIGHT LMS2 ID=4113,time=1225719876.121452,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=202,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.543,18.779,15.695,12.654,10.915,9.820,8.933,8.102,7.370,6.744,6.253,5.839,5.502,5.120,4.828,4.535,4.300,4.038,3.778,3.667,3.503,3.334,3.184,3.071,2.934,2.821,2.689,2.595,2.507,2.415,2.335,2.265,2.219,2.139,2.061,2.002,1.951,1.873,1.829,1.785,1.760,1.723,1.674,1.618,1.583,1.553,1.510,1.480,1.428,1.411,1.384,1.369,1.357,1.339,1.314,1.287,1.268,1.259,1.241,1.214,1.190,1.166,1.153,1.131,1.121,1.110,1.108,1.106,1.112,1.116,1.146,1.134,1.106,1.112,1.125,1.129,1.090,1.129,1.107,1.110,1.054,1.042,1.038,1.060,1.050,1.040,1.025,1.015,0.966,0.968},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,40.000,13.000,117.000,118.000,84.000,63.000,57.000,56.000,55.000,60.000,66.000,66.000,68.000,70.000,70.000,71.000,72.000,75.000,80.000,80.000,77.000,76.000,78.000,80.000,81.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,80.000,77.000,77.000,77.000,76.000,74.000,69.000,69.000,68.000,68.000,72.000,76.000,76.000,72.000,70.000,68.000,68.000,67.000,67.000,68.000,69.000,64.000,69.000,75.000,77.000,76.000,71.000,64.000,57.000,45.000,36.000,28.000,28.000,30.000,32.000,27.000,40.000,50.000,36.000,27.000,26.000,28.000,35.000,34.000,36.000,47.000,50.000,32.000,32.000}
-64.503 DESIRED_THRUST iJoystick 86.60237434
-64.503 DESIRED_RUDDER iJoystick 0
-64.475 LMS_LASER_2D_LEFT LMS1 ID=4241,time=1225719876.129282,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=238,Range=[181]{1.028,1.031,1.039,1.049,1.063,1.071,1.076,1.079,1.097,1.109,1.115,1.124,1.132,1.140,1.163,1.166,1.186,1.189,1.216,1.227,1.209,1.226,1.259,1.289,1.308,1.312,1.325,1.339,1.351,1.384,1.387,1.410,1.424,1.441,1.468,1.495,1.522,1.559,1.583,1.608,1.625,1.645,1.677,1.708,1.741,1.779,1.801,1.850,1.876,1.911,1.964,1.989,2.039,2.071,2.133,2.198,2.249,2.310,2.359,2.425,2.518,2.554,2.567,2.563,2.606,2.724,2.784,2.829,2.882,2.966,3.047,3.145,3.331,3.432,3.505,3.638,3.869,3.911,3.903,3.893,3.894,3.911,3.946,3.955,3.962,3.959,3.954,3.978,3.965,3.962,4.003,4.047,4.067,4.060,4.085,4.092,4.094,4.094,4.102,4.104,4.104,4.105,4.109,4.107,4.113,4.116,4.121,4.121,4.131,4.140,4.149,4.150,4.158,4.168,4.174,4.180,4.186,4.196,4.205,4.213,4.229,4.239,4.250,4.260,4.268,4.286,4.294,4.310,4.327,4.344,4.357,4.364,4.383,4.389,4.408,4.426,4.441,4.469,4.477,4.494,4.509,4.537,4.559,4.579,4.588,4.610,4.628,4.656,4.681,4.699,4.723,4.748,4.771,4.796,4.823,4.858,4.883,4.914,4.936,3.026,2.983,2.875,2.861,2.858,2.865,2.995,2.918,5.222,5.059,4.742,5.353,5.372,5.373,5.438,4.795,5.401,5.405,5.002,4.761,4.728,4.890},Reflectance=[181]{40.000,42.000,42.000,42.000,41.000,37.000,39.000,46.000,41.000,43.000,45.000,45.000,45.000,45.000,44.000,45.000,43.000,46.000,41.000,36.000,30.000,30.000,34.000,38.000,44.000,45.000,36.000,45.000,43.000,45.000,48.000,51.000,53.000,53.000,53.000,54.000,54.000,48.000,45.000,46.000,54.000,55.000,57.000,54.000,50.000,51.000,49.000,42.000,46.000,45.000,42.000,54.000,42.000,50.000,45.000,39.000,42.000,42.000,46.000,42.000,40.000,62.000,59.000,64.000,56.000,56.000,55.000,48.000,56.000,56.000,50.000,58.000,51.000,48.000,49.000,55.000,53.000,49.000,50.000,56.000,60.000,73.000,75.000,76.000,75.000,72.000,71.000,70.000,69.000,71.000,70.000,72.000,75.000,76.000,75.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,79.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,75.000,7.000,102.000,79.000,79.000,78.000,76.000,105.000,21.000,69.000,68.000,71.000,60.000,66.000,66.000,74.000,72.000,65.000,59.000,45.000,69.000,42.000,32.000}
-64.498 LMS_LASER_2D_RIGHT LMS2 ID=4114,time=1225719876.134799,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=203,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.603,-1.000,16.007,12.954,11.091,9.935,9.056,8.230,7.405,6.785,6.271,5.877,5.552,5.165,4.881,4.579,4.331,4.091,3.852,3.691,3.539,3.350,3.199,3.095,2.957,2.835,2.723,2.615,2.525,2.421,2.354,2.275,2.220,2.165,2.067,2.002,1.951,1.890,1.855,1.794,1.756,1.733,1.689,1.625,1.595,1.564,1.527,1.481,1.446,1.419,1.393,1.379,1.359,1.344,1.314,1.280,1.278,1.276,1.240,1.216,1.200,1.181,1.154,1.132,1.116,1.109,1.103,1.106,1.118,1.119,1.137,1.137,1.125,1.118,1.107,1.129,1.098,1.128,1.102,1.078,1.064,1.050,1.070,1.066,1.055,1.019,1.022,1.017,0.982,0.965},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,40.000,0.000,116.000,120.000,90.000,66.000,57.000,56.000,56.000,58.000,66.000,66.000,67.000,70.000,69.000,72.000,73.000,74.000,76.000,80.000,76.000,75.000,78.000,80.000,80.000,79.000,80.000,81.000,81.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,79.000,77.000,78.000,80.000,77.000,73.000,75.000,77.000,76.000,70.000,68.000,67.000,69.000,73.000,76.000,74.000,71.000,74.000,70.000,67.000,67.000,70.000,71.000,69.000,66.000,69.000,72.000,76.000,75.000,69.000,62.000,55.000,44.000,42.000,30.000,29.000,29.000,31.000,28.000,37.000,51.000,29.000,27.000,28.000,33.000,38.000,38.000,29.000,46.000,43.000,34.000,33.000}
-64.498 LMS_LASER_2D_LEFT LMS1 ID=4242,time=1225719876.142621,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=239,Range=[181]{1.031,1.031,1.037,1.046,1.057,1.064,1.073,1.085,1.090,1.101,1.115,1.124,1.126,1.140,1.157,1.176,1.174,1.201,1.212,1.225,1.237,1.236,1.270,1.287,1.298,1.316,1.333,1.334,1.366,1.382,1.394,1.412,1.424,1.442,1.469,1.500,1.512,1.552,1.586,1.610,1.624,1.643,1.670,1.706,1.738,1.772,1.795,1.839,1.873,1.919,1.951,1.991,2.034,2.074,2.128,2.185,2.240,2.300,2.353,2.420,2.499,2.574,2.567,2.571,2.594,2.698,2.786,2.816,2.878,2.932,3.034,3.129,3.238,3.417,3.493,3.608,3.829,3.905,3.901,3.902,3.881,3.909,3.936,3.946,3.953,3.951,3.954,3.971,3.965,3.965,3.996,4.033,4.054,4.051,4.076,4.092,4.091,4.093,4.093,4.101,4.102,4.103,4.104,4.104,4.104,4.114,4.121,4.121,4.129,4.130,4.140,4.149,4.156,4.166,4.164,4.181,4.178,4.195,4.196,4.220,4.220,4.240,4.241,4.252,4.269,4.278,4.294,4.308,4.327,4.335,4.346,4.363,4.374,4.390,4.399,4.424,4.443,4.461,4.467,4.485,4.511,4.528,4.543,4.568,4.593,4.603,4.628,4.645,4.663,4.698,4.724,4.740,4.763,4.790,4.824,4.850,4.877,4.907,4.930,4.963,3.031,2.875,2.863,2.852,2.863,2.872,2.903,5.220,4.763,4.707,4.734,5.373,5.383,5.404,4.948,5.401,5.445,5.119,4.836,4.707,5.184},Reflectance=[181]{38.000,42.000,41.000,41.000,42.000,41.000,42.000,40.000,42.000,43.000,45.000,46.000,47.000,46.000,45.000,43.000,46.000,42.000,39.000,42.000,38.000,32.000,35.000,38.000,39.000,39.000,36.000,32.000,37.000,41.000,47.000,52.000,53.000,53.000,54.000,52.000,50.000,52.000,43.000,47.000,53.000,54.000,54.000,53.000,49.000,43.000,50.000,45.000,41.000,46.000,40.000,48.000,40.000,42.000,48.000,41.000,42.000,45.000,46.000,44.000,40.000,54.000,59.000,61.000,59.000,56.000,48.000,50.000,55.000,56.000,55.000,59.000,56.000,50.000,51.000,58.000,57.000,54.000,49.000,52.000,58.000,72.000,75.000,75.000,75.000,72.000,71.000,71.000,69.000,71.000,71.000,71.000,74.000,76.000,75.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,79.000,79.000,78.000,78.000,78.000,77.000,76.000,76.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,77.000,76.000,75.000,121.000,78.000,79.000,79.000,77.000,75.000,51.000,71.000,77.000,71.000,74.000,64.000,63.000,72.000,82.000,65.000,63.000,72.000,63.000,53.000,35.000}
-64.511 LMS_LASER_2D_RIGHT LMS2 ID=4115,time=1225719876.148146,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=204,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.330,26.404,16.374,13.275,11.187,10.028,9.159,8.325,7.534,6.841,6.374,5.937,5.586,5.202,4.917,4.596,4.358,4.126,3.923,3.703,3.554,3.363,3.216,3.112,2.963,2.843,2.734,2.645,2.534,2.448,2.380,2.283,2.221,2.167,2.092,2.016,1.953,1.916,1.869,1.820,1.772,1.739,1.679,1.633,1.588,1.565,1.540,1.508,1.464,1.420,1.403,1.386,1.360,1.340,1.304,1.274,1.266,1.260,1.241,1.216,1.192,1.182,1.155,1.140,1.125,1.113,1.112,1.107,1.117,1.126,1.139,1.133,1.131,1.135,1.133,1.129,1.098,1.086,1.118,1.081,1.066,1.081,1.074,1.064,1.061,1.043,1.033,1.017,0.997,0.970},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,2.000,2.000,106.000,122.000,94.000,67.000,58.000,56.000,54.000,57.000,64.000,66.000,67.000,69.000,69.000,72.000,74.000,74.000,75.000,78.000,78.000,77.000,77.000,79.000,79.000,77.000,81.000,81.000,81.000,80.000,80.000,80.000,81.000,81.000,79.000,79.000,80.000,80.000,78.000,77.000,78.000,79.000,76.000,70.000,72.000,77.000,78.000,72.000,70.000,69.000,70.000,72.000,74.000,70.000,69.000,75.000,75.000,70.000,68.000,70.000,72.000,69.000,67.000,70.000,76.000,78.000,77.000,71.000,62.000,51.000,40.000,36.000,32.000,33.000,31.000,32.000,28.000,28.000,41.000,29.000,28.000,31.000,41.000,46.000,42.000,36.000,43.000,50.000,38.000,34.000}
-64.511 LMS_LASER_2D_LEFT LMS1 ID=4243,time=1225719876.155961,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=240,Range=[181]{1.025,1.035,1.039,1.041,1.054,1.066,1.075,1.080,1.092,1.097,1.114,1.124,1.127,1.144,1.150,1.166,1.178,1.195,1.207,1.219,1.237,1.254,1.268,1.281,1.294,1.287,1.298,1.314,1.365,1.382,1.397,1.402,1.425,1.443,1.468,1.488,1.521,1.547,1.578,1.605,1.632,1.655,1.664,1.697,1.736,1.772,1.800,1.831,1.878,1.920,1.933,1.983,2.030,2.069,2.124,2.172,2.231,2.293,2.342,2.408,2.495,2.559,2.566,2.572,2.588,2.714,2.787,2.814,2.860,2.962,3.029,3.126,3.216,3.396,3.482,3.577,3.792,3.891,3.906,3.904,3.885,3.896,3.929,3.946,3.954,3.948,3.952,3.967,3.967,3.959,3.988,4.032,4.054,4.050,4.066,4.092,4.091,4.091,4.092,4.100,4.101,4.101,4.103,4.104,4.105,4.113,4.113,4.121,4.121,4.130,4.140,4.148,4.155,4.156,4.165,4.173,4.180,4.193,4.194,4.214,4.218,4.230,4.242,4.251,4.259,4.277,4.285,4.300,4.320,4.335,4.348,4.355,4.375,4.391,4.399,4.416,4.434,4.457,4.465,4.485,4.501,4.519,4.544,4.572,4.587,4.610,4.625,4.637,4.663,4.690,4.715,4.739,4.763,4.789,4.814,4.841,4.874,4.902,4.923,4.954,2.942,2.948,2.861,2.850,2.847,2.856,2.875,2.913,4.677,4.599,4.647,4.861,5.382,5.427,5.436,5.401,5.437,5.088,5.011,4.741,5.062},Reflectance=[181]{39.000,40.000,45.000,43.000,41.000,42.000,43.000,46.000,43.000,41.000,41.000,42.000,48.000,48.000,47.000,45.000,44.000,40.000,41.000,39.000,38.000,36.000,37.000,39.000,35.000,30.000,30.000,30.000,35.000,38.000,44.000,51.000,50.000,54.000,53.000,51.000,54.000,54.000,48.000,49.000,53.000,51.000,55.000,53.000,48.000,48.000,52.000,50.000,39.000,42.000,49.000,39.000,41.000,44.000,45.000,43.000,42.000,46.000,46.000,47.000,42.000,55.000,58.000,61.000,56.000,48.000,49.000,49.000,47.000,51.000,49.000,58.000,58.000,49.000,46.000,60.000,56.000,55.000,51.000,57.000,56.000,71.000,75.000,75.000,75.000,71.000,70.000,69.000,69.000,72.000,71.000,71.000,74.000,76.000,75.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,75.000,39.000,101.000,79.000,79.000,78.000,75.000,63.000,19.000,79.000,67.000,65.000,78.000,61.000,71.000,71.000,65.000,61.000,40.000,61.000,49.000,42.000}
-64.519 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.4821,20.3970,-0.9417},Vel=[3x1]{-0.7663,-0.5576,2.8205},Raw=[2x1]{22.9252,-0.9417},time=1225719876.16662740707397,Speed=0.94769428462954,Pitch=0.03589365974142,Roll=0.02019018360455,PitchDot=-0.03589365974142,RollDot=-0.00074030673217
-64.519 ODOMETRY_POSE iPlatform Pose=[3x1]{6.4821,20.3970,-0.9414},Vel=[3x1]{-0.7663,-0.5576,2.8203},Raw=[2x1]{22.9252,-0.9417},time=1225719876.1666,Speed=0.9477,Pitch=0.0048,Roll=0.0409,PitchDot=0.0338,RollDot=0.0120
-64.524 LMS_LASER_2D_RIGHT LMS2 ID=4116,time=1225719876.161493,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=205,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.219,-1.000,16.931,13.693,11.342,10.158,9.237,8.378,7.618,6.933,6.432,6.007,5.637,5.246,4.954,4.630,4.395,4.169,3.952,3.735,3.574,3.407,3.244,3.118,2.979,2.855,2.761,2.637,2.543,2.456,2.372,2.310,2.238,2.157,2.074,2.021,1.976,1.925,1.881,1.829,1.787,1.740,1.698,1.622,1.589,1.569,1.549,1.520,1.492,1.440,1.419,1.387,1.359,1.332,1.314,1.282,1.265,1.253,1.243,1.217,1.191,1.165,1.149,1.134,1.118,1.118,1.114,1.115,1.127,1.128,1.127,1.125,1.116,1.119,1.112,1.113,1.110,1.084,1.074,1.074,1.065,1.095,1.076,1.065,1.057,1.048,1.041,1.020,0.997,0.978},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,0.000,88.000,125.000,98.000,68.000,58.000,57.000,56.000,57.000,63.000,66.000,67.000,69.000,69.000,72.000,74.000,74.000,75.000,77.000,79.000,78.000,78.000,78.000,79.000,78.000,80.000,81.000,81.000,79.000,80.000,80.000,80.000,80.000,79.000,78.000,80.000,80.000,79.000,79.000,77.000,77.000,77.000,75.000,73.000,76.000,78.000,77.000,73.000,74.000,75.000,73.000,72.000,72.000,76.000,74.000,75.000,73.000,71.000,71.000,70.000,68.000,70.000,73.000,74.000,77.000,76.000,71.000,62.000,51.000,44.000,34.000,30.000,30.000,28.000,29.000,29.000,28.000,27.000,27.000,27.000,37.000,43.000,46.000,46.000,41.000,43.000,37.000,30.000,34.000}
-64.524 LMS_LASER_2D_RIGHT LMS2 ID=4117,time=1225719876.174828,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=206,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.321,17.093,13.778,11.547,10.276,9.335,8.502,7.708,7.038,6.512,6.052,5.663,5.283,4.981,4.655,4.447,4.185,3.974,3.767,3.598,3.442,3.256,3.122,3.010,2.872,2.770,2.644,2.564,2.447,2.361,2.309,2.256,2.183,2.093,2.033,1.982,1.933,1.890,1.838,1.784,1.746,1.702,1.634,1.596,1.570,1.551,1.513,1.479,1.449,1.432,1.396,1.360,1.332,1.320,1.300,1.279,1.252,1.244,1.225,1.197,1.174,1.155,1.142,1.117,1.123,1.110,1.115,1.124,1.123,1.132,1.137,1.110,1.101,1.112,1.116,1.131,1.107,1.080,1.071,1.065,1.094,1.084,1.068,1.061,1.049,1.048,1.032,0.988,0.978},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,10.000,84.000,127.000,99.000,72.000,58.000,56.000,56.000,59.000,63.000,66.000,67.000,68.000,69.000,72.000,72.000,74.000,74.000,77.000,78.000,78.000,76.000,80.000,81.000,80.000,80.000,81.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,80.000,79.000,79.000,78.000,78.000,77.000,69.000,72.000,76.000,75.000,75.000,77.000,76.000,74.000,72.000,72.000,75.000,75.000,71.000,72.000,72.000,69.000,66.000,70.000,75.000,74.000,73.000,75.000,74.000,70.000,61.000,53.000,49.000,37.000,29.000,28.000,28.000,29.000,32.000,29.000,27.000,27.000,27.000,35.000,43.000,39.000,37.000,38.000,42.000,47.000,29.000,34.000}
-64.527 DESIRED_THRUST iJoystick 86.60237434
-64.527 DESIRED_RUDDER iJoystick 0
-64.525 LMS_LASER_2D_LEFT LMS1 ID=4244,time=1225719876.169300,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=241,Range=[181]{1.025,1.034,1.030,1.050,1.060,1.068,1.067,1.085,1.090,1.090,1.107,1.118,1.124,1.140,1.149,1.164,1.176,1.194,1.209,1.218,1.232,1.247,1.264,1.276,1.300,1.287,1.332,1.342,1.357,1.371,1.394,1.404,1.430,1.444,1.469,1.491,1.522,1.533,1.572,1.602,1.620,1.659,1.681,1.689,1.731,1.768,1.794,1.830,1.869,1.918,1.941,1.977,2.024,2.057,2.108,2.162,2.225,2.279,2.340,2.403,2.479,2.518,2.554,2.563,2.589,2.714,2.774,2.820,2.868,2.957,3.014,3.103,3.244,3.356,3.474,3.574,3.791,3.887,3.898,3.895,3.893,3.894,3.916,3.947,3.953,3.947,3.943,3.961,3.964,3.957,3.980,4.018,4.051,4.052,4.057,4.092,4.093,4.090,4.091,4.090,4.099,4.099,4.103,4.104,4.107,4.114,4.112,4.122,4.121,4.130,4.139,4.149,4.157,4.156,4.164,4.174,4.180,4.186,4.195,4.203,4.220,4.231,4.240,4.249,4.260,4.269,4.285,4.293,4.321,4.327,4.345,4.356,4.372,4.381,4.398,4.416,4.433,4.446,4.458,4.476,4.493,4.520,4.536,4.562,4.591,4.604,4.624,4.636,4.654,4.681,4.707,4.732,4.755,4.779,4.809,4.834,4.866,4.891,4.916,4.945,4.972,3.000,2.858,2.842,2.841,2.842,2.860,2.905,4.663,4.585,4.579,4.679,5.381,5.403,5.440,5.401,5.419,5.279,5.074,5.088,5.072},Reflectance=[181]{38.000,40.000,46.000,43.000,39.000,43.000,43.000,43.000,42.000,42.000,45.000,43.000,46.000,45.000,42.000,46.000,43.000,39.000,38.000,38.000,41.000,37.000,40.000,35.000,36.000,30.000,35.000,43.000,35.000,37.000,43.000,44.000,48.000,54.000,54.000,52.000,54.000,55.000,53.000,52.000,52.000,49.000,54.000,54.000,49.000,45.000,50.000,46.000,38.000,41.000,44.000,37.000,43.000,47.000,47.000,48.000,48.000,48.000,44.000,41.000,47.000,63.000,61.000,61.000,56.000,48.000,47.000,48.000,46.000,52.000,51.000,52.000,48.000,47.000,47.000,58.000,55.000,53.000,51.000,53.000,56.000,71.000,75.000,76.000,75.000,71.000,70.000,68.000,69.000,71.000,71.000,69.000,73.000,76.000,75.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,79.000,79.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,75.000,76.000,117.000,79.000,79.000,79.000,77.000,74.000,48.000,82.000,71.000,69.000,80.000,60.000,72.000,72.000,66.000,63.000,68.000,74.000,53.000,50.000}
-64.538 LMS_LASER_2D_RIGHT LMS2 ID=4118,time=1225719876.188162,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=207,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.368,17.334,14.307,11.964,10.362,9.424,8.580,7.780,7.088,6.545,6.097,5.671,5.311,4.990,4.681,4.448,4.221,3.992,3.801,3.610,3.433,3.243,3.135,3.018,2.898,2.781,2.670,2.574,2.468,2.397,2.306,2.255,2.174,2.100,2.025,1.977,1.935,1.882,1.829,1.794,1.745,1.711,1.663,1.604,1.568,1.551,1.516,1.475,1.455,1.435,1.406,1.382,1.342,1.330,1.310,1.288,1.260,1.244,1.230,1.195,1.168,1.164,1.134,1.134,1.125,1.125,1.122,1.119,1.120,1.131,1.141,1.123,1.119,1.110,1.127,1.104,1.093,1.080,1.068,1.060,1.076,1.067,1.074,1.061,1.062,1.036,1.030,1.009,0.970},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,77.000,120.000,97.000,75.000,57.000,55.000,57.000,57.000,63.000,65.000,67.000,69.000,70.000,72.000,72.000,74.000,74.000,76.000,77.000,78.000,78.000,81.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,79.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,77.000,67.000,67.000,68.000,70.000,74.000,76.000,77.000,77.000,75.000,74.000,75.000,75.000,71.000,69.000,73.000,64.000,63.000,73.000,75.000,73.000,73.000,73.000,73.000,69.000,63.000,59.000,52.000,41.000,32.000,30.000,30.000,32.000,28.000,28.000,27.000,26.000,27.000,30.000,30.000,34.000,39.000,45.000,44.000,45.000,35.000,31.000}
-64.538 LMS_LASER_2D_LEFT LMS1 ID=4245,time=1225719876.182640,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=242,Range=[181]{1.028,1.025,1.039,1.043,1.060,1.060,1.071,1.081,1.089,1.092,1.102,1.114,1.124,1.140,1.157,1.167,1.175,1.193,1.201,1.217,1.229,1.245,1.259,1.276,1.289,1.303,1.324,1.344,1.362,1.376,1.395,1.414,1.431,1.444,1.465,1.501,1.502,1.526,1.560,1.590,1.620,1.652,1.680,1.699,1.725,1.763,1.788,1.821,1.858,1.909,1.943,1.985,2.019,2.061,2.108,2.157,2.207,2.269,2.331,2.389,2.464,2.502,2.537,2.554,2.579,2.712,2.773,2.818,2.859,2.937,3.006,3.094,3.218,3.327,3.477,3.566,3.800,3.887,3.901,3.897,3.896,3.888,3.916,3.945,3.954,3.950,3.947,3.961,3.959,3.949,3.976,4.016,4.051,4.049,4.048,4.081,4.083,4.093,4.093,4.090,4.101,4.094,4.095,4.096,4.104,4.104,4.113,4.113,4.121,4.120,4.130,4.141,4.149,4.157,4.165,4.172,4.172,4.186,4.195,4.204,4.221,4.224,4.233,4.240,4.258,4.267,4.277,4.304,4.310,4.325,4.338,4.345,4.364,4.380,4.390,4.407,4.424,4.445,4.458,4.475,4.494,4.519,4.536,4.561,4.592,4.599,4.625,4.635,4.655,4.681,4.699,4.731,4.757,4.781,4.806,4.833,4.857,4.891,4.918,4.944,4.971,2.898,2.925,2.837,2.833,2.830,2.847,2.867,4.711,4.606,4.569,4.578,5.378,5.396,5.434,5.401,5.401,5.266,5.128,5.082,5.056},Reflectance=[181]{40.000,48.000,45.000,40.000,39.000,44.000,41.000,45.000,45.000,43.000,48.000,46.000,45.000,45.000,45.000,42.000,47.000,43.000,42.000,34.000,40.000,36.000,38.000,37.000,39.000,34.000,43.000,44.000,40.000,42.000,43.000,44.000,49.000,54.000,48.000,52.000,57.000,60.000,55.000,53.000,52.000,37.000,54.000,50.000,47.000,43.000,47.000,50.000,42.000,41.000,37.000,37.000,41.000,44.000,47.000,50.000,48.000,47.000,48.000,45.000,49.000,67.000,69.000,65.000,60.000,51.000,46.000,47.000,46.000,51.000,52.000,48.000,48.000,46.000,48.000,55.000,49.000,49.000,49.000,54.000,53.000,69.000,75.000,75.000,75.000,72.000,71.000,70.000,70.000,72.000,72.000,69.000,73.000,75.000,75.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,75.000,75.000,56.000,95.000,79.000,79.000,78.000,75.000,57.000,77.000,75.000,69.000,67.000,59.000,73.000,73.000,66.000,65.000,67.000,79.000,54.000,58.000}
-64.550 LMS_LASER_2D_RIGHT LMS2 ID=4119,time=1225719876.201495,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=208,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.365,17.465,14.800,12.044,10.407,9.435,8.622,7.809,7.088,6.580,6.126,5.681,5.328,5.007,4.707,4.484,4.230,4.003,3.791,3.610,3.452,3.248,3.151,3.036,2.891,2.772,2.688,2.586,2.471,2.397,2.300,2.257,2.150,2.098,2.019,1.967,1.944,1.884,1.830,1.786,1.744,1.706,1.671,1.614,1.577,1.552,1.517,1.489,1.470,1.432,1.413,1.374,1.351,1.324,1.305,1.279,1.268,1.244,1.224,1.196,1.182,1.159,1.143,1.130,1.127,1.121,1.115,1.112,1.119,1.112,1.120,1.129,1.113,1.127,1.127,1.127,1.104,1.090,1.074,1.065,1.051,1.083,1.071,1.063,1.048,1.031,1.034,1.014,0.977},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,72.000,107.000,106.000,78.000,58.000,55.000,57.000,57.000,63.000,65.000,68.000,69.000,70.000,72.000,73.000,74.000,75.000,76.000,76.000,78.000,79.000,80.000,80.000,81.000,81.000,80.000,80.000,81.000,80.000,80.000,81.000,81.000,78.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,76.000,76.000,69.000,67.000,70.000,72.000,75.000,75.000,74.000,76.000,75.000,73.000,73.000,71.000,71.000,75.000,74.000,68.000,64.000,69.000,73.000,74.000,75.000,74.000,75.000,70.000,65.000,63.000,60.000,51.000,40.000,29.000,32.000,31.000,32.000,28.000,27.000,27.000,27.000,27.000,36.000,45.000,45.000,46.000,50.000,43.000,38.000,33.000}
-64.551 DESIRED_THRUST iJoystick 86.60237434
-64.551 DESIRED_RUDDER iJoystick 0
-64.555 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.5133,20.4197,-0.9423},Vel=[3x1]{-0.7631,-0.5546,0.8974},Raw=[2x1]{22.9637,-0.9423},time=1225719876.20254731178284,Speed=0.94331357144943,Pitch=0.03365030600758,Roll=0.01794682987071,PitchDot=-0.04038036720910,RollDot=-0.00008973414935
-64.555 ODOMETRY_POSE iPlatform Pose=[3x1]{6.5133,20.4197,-0.9421},Vel=[3x1]{-0.7631,-0.5546,0.8978},Raw=[2x1]{22.9637,-0.9423},time=1225719876.2025,Speed=0.9433,Pitch=0.0053,Roll=0.0378,PitchDot=-0.0252,RollDot=0.0315
-64.555 VEHICLE_GEOMETRY iPlatform Name=LISA, Sensor_0=LMS_LASER_2D, Pose3D_0=[4x1]{0.0000,0.3500,0.0000,0.0000},SHAPE_2D=[2x8]{0.3300,0.3300,0.2100,0.2100,-0.2100,-0.2100,-0.3300,-0.3300,-0.4100,0.4100,0.4100,0.5700,0.5700,0.4100,0.4100,-0.4100,}
-64.550 LMS_LASER_2D_LEFT LMS1 ID=4246,time=1225719876.195978,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=243,Range=[181]{1.017,1.032,1.039,1.050,1.059,1.067,1.073,1.081,1.084,1.099,1.105,1.125,1.132,1.139,1.149,1.166,1.176,1.198,1.203,1.201,1.232,1.237,1.257,1.241,1.287,1.300,1.312,1.330,1.361,1.376,1.394,1.416,1.426,1.443,1.472,1.485,1.494,1.511,1.547,1.599,1.616,1.658,1.681,1.698,1.732,1.764,1.789,1.822,1.867,1.902,1.927,1.975,2.011,2.054,2.103,2.155,2.210,2.267,2.326,2.384,2.455,2.500,2.540,2.552,2.572,2.711,2.761,2.817,2.856,2.925,3.014,3.090,3.204,3.306,3.469,3.573,3.799,3.888,3.906,3.895,3.896,3.878,3.915,3.937,3.945,3.954,3.946,3.953,3.967,3.949,3.979,4.009,4.051,4.049,4.048,4.080,4.086,4.085,4.091,4.092,4.092,4.091,4.095,4.104,4.103,4.113,4.112,4.113,4.120,4.121,4.131,4.140,4.141,4.156,4.165,4.163,4.174,4.178,4.189,4.205,4.214,4.231,4.233,4.242,4.250,4.267,4.276,4.288,4.309,4.325,4.338,4.352,4.363,4.379,4.387,4.413,4.425,4.447,4.457,4.476,4.494,4.509,4.537,4.551,4.582,4.601,4.618,4.636,4.655,4.670,4.699,4.724,4.754,4.771,4.797,4.824,4.858,4.885,4.918,4.938,4.964,2.927,2.948,2.832,2.823,2.831,2.831,2.835,2.902,4.632,4.606,4.550,5.381,5.391,5.436,5.411,5.401,5.158,5.099,5.089,5.011},Reflectance=[181]{43.000,42.000,42.000,39.000,39.000,43.000,45.000,45.000,43.000,42.000,40.000,38.000,42.000,45.000,45.000,42.000,43.000,40.000,39.000,32.000,37.000,33.000,37.000,29.000,35.000,49.000,54.000,46.000,38.000,42.000,43.000,45.000,46.000,46.000,43.000,53.000,63.000,63.000,58.000,54.000,54.000,39.000,45.000,50.000,50.000,43.000,47.000,45.000,45.000,45.000,33.000,40.000,46.000,46.000,49.000,49.000,50.000,45.000,50.000,48.000,49.000,65.000,72.000,71.000,64.000,54.000,49.000,46.000,49.000,49.000,47.000,50.000,49.000,48.000,53.000,54.000,48.000,46.000,47.000,49.000,50.000,66.000,74.000,75.000,75.000,73.000,71.000,70.000,72.000,72.000,73.000,69.000,73.000,75.000,75.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,76.000,76.000,24.000,109.000,79.000,79.000,78.000,76.000,67.000,18.000,77.000,72.000,63.000,60.000,71.000,74.000,67.000,66.000,62.000,74.000,58.000,64.000}
-64.562 LMS_LASER_2D_RIGHT LMS2 ID=4120,time=1225719876.214827,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=209,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.403,17.360,14.227,12.071,10.415,9.461,8.675,7.851,7.102,6.580,6.144,5.681,5.327,5.016,4.716,4.483,4.197,3.999,3.796,3.599,3.453,3.261,3.150,3.045,2.898,2.796,2.697,2.588,2.485,2.397,2.289,2.256,2.184,2.095,2.036,1.982,1.953,1.884,1.838,1.785,1.758,1.707,1.664,1.617,1.594,1.560,1.509,1.487,1.462,1.430,1.407,1.383,1.360,1.331,1.310,1.288,1.270,1.244,1.223,1.195,1.165,1.150,1.142,1.134,1.124,1.108,1.115,1.114,1.120,1.112,1.108,1.126,1.130,1.130,1.110,1.113,1.130,1.130,1.115,1.072,1.095,1.092,1.074,1.059,1.047,1.033,1.026,1.015,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,18.000,77.000,123.000,107.000,78.000,58.000,54.000,56.000,55.000,63.000,65.000,67.000,69.000,70.000,72.000,72.000,75.000,73.000,75.000,76.000,78.000,78.000,79.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,79.000,79.000,74.000,74.000,74.000,75.000,76.000,74.000,75.000,75.000,72.000,74.000,75.000,74.000,69.000,65.000,71.000,76.000,73.000,66.000,64.000,69.000,72.000,74.000,73.000,72.000,74.000,70.000,68.000,64.000,64.000,57.000,47.000,35.000,35.000,29.000,30.000,35.000,40.000,34.000,27.000,35.000,47.000,46.000,39.000,38.000,47.000,44.000,41.000,36.000}
-64.562 LMS_LASER_2D_LEFT LMS1 ID=4247,time=1225719876.209315,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=244,Range=[181]{1.020,1.033,1.038,1.041,1.052,1.061,1.073,1.074,1.092,1.103,1.116,1.121,1.132,1.134,1.153,1.166,1.173,1.201,1.206,1.204,1.230,1.241,1.263,1.277,1.285,1.302,1.294,1.322,1.366,1.375,1.392,1.405,1.432,1.446,1.469,1.472,1.485,1.521,1.558,1.600,1.618,1.647,1.675,1.702,1.730,1.760,1.790,1.822,1.866,1.894,1.941,1.975,2.011,2.051,2.108,2.158,2.221,2.268,2.333,2.384,2.462,2.509,2.529,2.551,2.581,2.695,2.755,2.809,2.869,2.911,2.995,3.082,3.207,3.296,3.453,3.590,3.809,3.874,3.898,3.897,3.888,3.878,3.915,3.937,3.946,3.955,3.948,3.954,3.960,3.949,3.968,4.009,4.042,4.050,4.055,4.081,4.084,4.084,4.084,4.091,4.092,4.101,4.093,4.096,4.104,4.104,4.104,4.112,4.122,4.119,4.129,4.131,4.140,4.149,4.156,4.172,4.174,4.185,4.187,4.202,4.213,4.223,4.233,4.240,4.252,4.267,4.275,4.289,4.308,4.319,4.334,4.351,4.360,4.377,4.386,4.404,4.425,4.437,4.448,4.466,4.492,4.509,4.537,4.554,4.584,4.600,4.618,4.635,4.655,4.671,4.698,4.735,4.747,4.772,4.796,4.824,4.858,4.884,4.910,4.939,4.966,4.999,2.977,2.831,2.824,2.821,2.824,2.838,2.861,4.604,4.599,4.595,5.389,5.349,4.533,5.401,5.401,5.106,5.059,5.037,4.783},Reflectance=[181]{41.000,43.000,46.000,43.000,40.000,44.000,42.000,47.000,43.000,44.000,42.000,44.000,45.000,43.000,44.000,45.000,41.000,36.000,37.000,32.000,37.000,35.000,39.000,38.000,34.000,45.000,54.000,47.000,45.000,46.000,46.000,44.000,53.000,48.000,46.000,55.000,62.000,58.000,55.000,51.000,51.000,43.000,52.000,52.000,49.000,46.000,48.000,45.000,42.000,46.000,39.000,40.000,46.000,48.000,47.000,45.000,46.000,42.000,46.000,48.000,48.000,62.000,69.000,73.000,64.000,55.000,50.000,47.000,47.000,50.000,47.000,54.000,50.000,47.000,46.000,53.000,49.000,48.000,47.000,50.000,50.000,66.000,74.000,75.000,75.000,73.000,71.000,71.000,70.000,72.000,72.000,69.000,74.000,76.000,75.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,76.000,77.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,76.000,76.000,76.000,119.000,78.000,79.000,78.000,76.000,73.000,31.000,74.000,72.000,63.000,59.000,70.000,7.000,66.000,66.000,65.000,68.000,61.000,66.000}
-64.575 LMS_LASER_2D_RIGHT LMS2 ID=4121,time=1225719876.228158,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=210,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,26.465,17.317,14.163,12.009,10.398,9.412,8.629,7.822,7.060,6.537,6.108,5.689,5.318,4.998,4.700,4.466,4.203,3.971,3.763,3.598,3.452,3.288,3.149,3.014,2.880,2.795,2.688,2.598,2.477,2.397,2.298,2.256,2.193,2.114,2.053,1.994,1.953,1.890,1.832,1.794,1.747,1.710,1.668,1.630,1.595,1.565,1.527,1.504,1.461,1.438,1.412,1.378,1.359,1.328,1.309,1.286,1.264,1.250,1.219,1.221,1.199,1.166,1.150,1.126,1.125,1.117,1.108,1.106,1.106,1.103,1.106,1.116,1.130,1.133,1.116,1.137,1.127,1.121,1.110,1.113,1.096,1.081,1.067,1.059,1.047,1.036,1.025,1.021,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,23.000,77.000,122.000,106.000,75.000,60.000,54.000,55.000,57.000,64.000,66.000,67.000,68.000,70.000,72.000,72.000,74.000,72.000,76.000,75.000,78.000,78.000,79.000,81.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,77.000,76.000,78.000,78.000,77.000,74.000,75.000,75.000,70.000,70.000,71.000,72.000,65.000,63.000,69.000,74.000,68.000,62.000,64.000,69.000,70.000,72.000,74.000,72.000,73.000,73.000,70.000,71.000,64.000,60.000,53.000,37.000,38.000,30.000,40.000,51.000,56.000,54.000,48.000,45.000,46.000,47.000,43.000,46.000,45.000,47.000,42.000,34.000}
-64.575 LMS_LASER_2D_LEFT LMS1 ID=4248,time=1225719876.222652,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=245,Range=[181]{1.016,1.036,1.028,1.042,1.056,1.067,1.075,1.084,1.091,1.103,1.109,1.113,1.127,1.140,1.148,1.171,1.174,1.193,1.188,1.211,1.236,1.232,1.262,1.271,1.285,1.298,1.295,1.327,1.354,1.370,1.389,1.408,1.424,1.443,1.476,1.478,1.476,1.516,1.564,1.597,1.620,1.653,1.670,1.703,1.724,1.756,1.788,1.827,1.868,1.897,1.938,1.983,2.011,2.056,2.110,2.159,2.208,2.275,2.331,2.389,2.470,2.521,2.535,2.554,2.581,2.695,2.752,2.807,2.868,2.916,2.978,3.077,3.214,3.294,3.444,3.637,3.798,3.880,3.896,3.894,3.878,3.879,3.912,3.937,3.954,3.946,3.948,3.954,3.959,3.951,3.964,4.011,4.041,4.051,4.048,4.078,4.085,4.084,4.093,4.091,4.091,4.094,4.095,4.088,4.095,4.103,4.112,4.112,4.122,4.121,4.130,4.131,4.140,4.147,4.156,4.163,4.174,4.187,4.193,4.195,4.212,4.226,4.231,4.242,4.252,4.266,4.275,4.291,4.307,4.318,4.334,4.343,4.362,4.378,4.386,4.405,4.424,4.445,4.448,4.467,4.494,4.510,4.528,4.554,4.574,4.594,4.619,4.637,4.645,4.672,4.698,4.722,4.747,4.772,4.796,4.825,4.860,4.883,4.910,4.933,4.968,5.003,2.996,2.829,2.815,2.813,2.806,2.826,2.859,4.581,4.578,4.603,4.851,4.680,4.696,4.732,4.916,5.101,5.056,4.777,4.681},Reflectance=[181]{43.000,44.000,46.000,43.000,42.000,43.000,43.000,43.000,38.000,44.000,43.000,46.000,43.000,45.000,45.000,40.000,42.000,34.000,32.000,33.000,38.000,33.000,38.000,43.000,35.000,52.000,54.000,44.000,49.000,48.000,44.000,46.000,53.000,54.000,49.000,58.000,66.000,56.000,53.000,53.000,52.000,46.000,54.000,52.000,54.000,49.000,51.000,44.000,45.000,48.000,47.000,39.000,46.000,45.000,43.000,45.000,44.000,41.000,48.000,46.000,43.000,55.000,63.000,63.000,63.000,55.000,49.000,50.000,50.000,49.000,47.000,48.000,50.000,46.000,50.000,47.000,48.000,46.000,46.000,52.000,57.000,66.000,73.000,75.000,75.000,73.000,71.000,71.000,70.000,72.000,71.000,70.000,73.000,76.000,75.000,76.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,126.000,78.000,79.000,78.000,76.000,74.000,50.000,72.000,72.000,63.000,75.000,85.000,94.000,85.000,81.000,67.000,69.000,72.000,66.000}
-64.575 DESIRED_THRUST iJoystick 86.60237434
-64.575 DESIRED_RUDDER iJoystick 0
-64.591 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.5441,20.4420,-0.9425},Vel=[3x1]{-0.7632,-0.5545,0.7692},Raw=[2x1]{23.0018,-0.9425},time=1225719876.23864746093750,Speed=0.94331357144943,Pitch=0.03140695227374,Roll=0.01570347613687,PitchDot=-0.05384048961213,RollDot=-0.00008973414935
-64.591 ODOMETRY_POSE iPlatform Pose=[3x1]{6.5441,20.4420,-0.9424},Vel=[3x1]{-0.7632,-0.5545,0.7699},Raw=[2x1]{23.0018,-0.9425},time=1225719876.2386,Speed=0.9433,Pitch=0.0058,Roll=0.0346,PitchDot=-0.0387,RollDot=0.0374
-64.587 LMS_LASER_2D_LEFT LMS1 ID=4249,time=1225719876.235987,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=246,Range=[181]{1.022,1.039,1.033,1.046,1.050,1.064,1.071,1.087,1.089,1.100,1.116,1.115,1.130,1.140,1.160,1.163,1.185,1.194,1.178,1.195,1.232,1.244,1.262,1.273,1.287,1.285,1.295,1.329,1.358,1.378,1.400,1.405,1.420,1.443,1.467,1.493,1.494,1.520,1.564,1.598,1.625,1.663,1.670,1.700,1.735,1.765,1.793,1.822,1.860,1.895,1.938,1.973,2.019,2.064,2.111,2.159,2.221,2.278,2.326,2.392,2.465,2.548,2.566,2.558,2.581,2.701,2.757,2.811,2.868,2.911,2.972,3.078,3.231,3.299,3.469,3.675,3.798,3.886,3.898,3.895,3.875,3.876,3.914,3.937,3.946,3.945,3.946,3.952,3.959,3.949,3.970,4.013,4.043,4.050,4.057,4.079,4.082,4.086,4.083,4.083,4.092,4.093,4.096,4.096,4.103,4.103,4.113,4.112,4.120,4.119,4.130,4.131,4.140,4.147,4.155,4.164,4.174,4.180,4.194,4.195,4.215,4.215,4.231,4.251,4.252,4.267,4.276,4.291,4.305,4.316,4.336,4.353,4.370,4.378,4.386,4.408,4.425,4.438,4.451,4.466,4.485,4.509,4.528,4.555,4.583,4.593,4.618,4.634,4.653,4.672,4.698,4.723,4.748,4.770,4.796,4.833,3.348,4.890,4.917,4.942,4.970,5.002,2.866,2.830,2.807,2.811,2.799,2.811,2.966,4.587,4.543,4.578,4.697,4.510,4.646,4.645,4.695,5.114,5.064,4.702,4.646},Reflectance=[181]{42.000,45.000,43.000,41.000,43.000,45.000,46.000,37.000,45.000,42.000,42.000,46.000,46.000,45.000,43.000,40.000,38.000,39.000,31.000,31.000,40.000,38.000,43.000,39.000,34.000,54.000,54.000,50.000,47.000,43.000,45.000,52.000,52.000,54.000,53.000,53.000,61.000,58.000,53.000,54.000,50.000,46.000,54.000,47.000,51.000,44.000,44.000,45.000,43.000,51.000,47.000,43.000,44.000,45.000,48.000,46.000,46.000,48.000,46.000,48.000,44.000,45.000,54.000,59.000,61.000,50.000,51.000,52.000,54.000,50.000,48.000,52.000,50.000,49.000,53.000,47.000,48.000,46.000,47.000,53.000,59.000,68.000,74.000,75.000,75.000,73.000,71.000,70.000,70.000,72.000,70.000,70.000,74.000,76.000,75.000,76.000,77.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,2.000,77.000,77.000,77.000,77.000,77.000,57.000,78.000,79.000,78.000,77.000,75.000,109.000,74.000,69.000,67.000,80.000,75.000,92.000,83.000,84.000,63.000,69.000,75.000,69.000}
-64.598 LMS_LASER_2D_RIGHT LMS2 ID=4122,time=1225719876.241499,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=211,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,26.451,17.206,13.972,11.930,10.332,9.358,8.594,7.787,7.043,6.520,6.078,5.671,5.318,4.981,4.681,4.457,4.196,3.964,3.774,3.590,3.453,3.275,3.140,2.959,2.869,2.778,2.670,2.570,2.476,2.386,2.318,2.256,2.192,2.122,2.053,2.002,1.959,1.889,1.827,1.774,1.728,1.707,1.667,1.622,1.593,1.557,1.540,1.514,1.472,1.439,1.411,1.379,1.360,1.338,1.309,1.293,1.269,1.257,1.232,1.208,1.192,1.168,1.159,1.142,1.133,1.123,1.115,1.106,1.099,1.103,1.106,1.118,1.124,1.127,1.116,1.143,1.125,1.117,1.109,1.098,1.101,1.070,1.061,1.054,1.046,1.035,1.030,1.010,0.977},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,10.000,78.000,124.000,104.000,74.000,60.000,54.000,55.000,57.000,64.000,65.000,67.000,68.000,70.000,72.000,73.000,74.000,73.000,76.000,76.000,78.000,79.000,80.000,83.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,75.000,78.000,75.000,72.000,68.000,74.000,72.000,66.000,63.000,66.000,70.000,65.000,66.000,70.000,71.000,72.000,72.000,73.000,71.000,69.000,69.000,71.000,72.000,65.000,57.000,50.000,36.000,32.000,30.000,43.000,50.000,54.000,54.000,53.000,47.000,52.000,52.000,52.000,52.000,51.000,49.000,39.000,33.000}
-64.598 LMS_LASER_2D_LEFT LMS1 ID=4250,time=1225719876.249321,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=247,Range=[181]{1.024,1.035,1.039,1.043,1.060,1.062,1.075,1.088,1.090,1.107,1.115,1.122,1.127,1.136,1.156,1.161,1.169,1.173,1.168,1.184,1.234,1.230,1.263,1.276,1.294,1.293,1.303,1.328,1.352,1.375,1.396,1.409,1.434,1.452,1.469,1.502,1.520,1.538,1.581,1.601,1.632,1.660,1.670,1.698,1.733,1.757,1.803,1.836,1.868,1.912,1.945,1.979,2.030,2.071,2.117,2.171,2.206,2.289,2.340,2.403,2.473,2.552,2.566,2.561,2.586,2.714,2.767,2.817,2.873,2.913,2.973,3.083,3.245,3.312,3.487,3.686,3.813,3.889,3.899,3.874,3.865,3.885,3.925,3.936,3.943,3.951,3.948,3.950,3.953,3.947,3.972,4.010,4.043,4.041,4.055,4.081,4.074,4.086,4.084,4.092,4.093,4.093,4.096,4.095,4.095,4.102,4.111,4.111,4.121,4.120,4.131,4.132,4.139,4.146,4.153,4.165,4.172,4.177,4.196,4.194,4.214,4.226,4.232,4.250,4.258,4.267,4.276,4.290,4.308,4.327,4.346,4.354,4.372,4.381,4.390,4.410,4.427,4.440,4.448,4.466,4.494,4.510,4.528,4.554,4.575,4.594,4.620,4.644,4.653,4.672,4.699,4.732,4.747,4.777,4.803,4.832,3.233,3.213,3.109,4.945,4.970,5.010,2.881,2.883,2.804,2.792,2.793,2.800,2.942,4.609,4.537,4.558,4.605,4.493,4.610,4.666,4.678,4.809,4.907,4.665,4.630},Reflectance=[181]{47.000,44.000,42.000,44.000,44.000,46.000,43.000,41.000,45.000,42.000,45.000,41.000,43.000,44.000,40.000,37.000,32.000,32.000,27.000,28.000,34.000,32.000,43.000,41.000,41.000,53.000,54.000,53.000,48.000,46.000,48.000,54.000,50.000,54.000,54.000,53.000,53.000,54.000,53.000,51.000,53.000,53.000,54.000,54.000,50.000,49.000,45.000,44.000,46.000,47.000,45.000,42.000,41.000,40.000,43.000,52.000,52.000,44.000,44.000,44.000,44.000,43.000,54.000,60.000,59.000,48.000,47.000,50.000,56.000,51.000,52.000,51.000,48.000,47.000,56.000,48.000,47.000,47.000,48.000,59.000,69.000,68.000,74.000,75.000,75.000,72.000,71.000,69.000,70.000,71.000,71.000,69.000,74.000,76.000,75.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,21.000,5.000,21.000,78.000,77.000,76.000,56.000,98.000,78.000,77.000,77.000,77.000,110.000,78.000,68.000,69.000,79.000,76.000,88.000,84.000,83.000,76.000,67.000,74.000,69.000}
-64.599 DESIRED_THRUST iJoystick 86.60237434
-64.599 DESIRED_RUDDER iJoystick 0
-64.623 DESIRED_THRUST iJoystick 86.60237434
-64.623 DESIRED_RUDDER iJoystick 0
-64.628 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.5665,20.4584,-0.9419},Vel=[3x1]{-0.7440,-0.5411,-4.2308},Raw=[2x1]{23.0296,-0.9419},time=1225719876.27552652359009,Speed=0.91994976782220,Pitch=0.03140695227374,Roll=0.01570347613687,PitchDot=-0.05384048961213,RollDot=0.00060570550814
-64.628 ODOMETRY_POSE iPlatform Pose=[3x1]{6.5665,20.4584,-0.9418},Vel=[3x1]{-0.7440,-0.5411,2.0518},Raw=[2x1]{23.0296,-0.9419},time=1225719876.2755,Speed=0.9199,Pitch=0.0058,Roll=0.0346,PitchDot=0.0255,RollDot=0.0474
-64.611 LMS_LASER_2D_RIGHT LMS2 ID=4123,time=1225719876.254839,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=212,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.356,26.572,17.020,13.854,11.741,10.232,9.268,8.471,7.766,7.023,6.520,6.061,5.637,5.291,4.971,4.671,4.447,4.187,3.958,3.758,3.590,3.443,3.273,3.130,3.001,2.869,2.766,2.669,2.559,2.459,2.386,2.310,2.256,2.184,2.131,2.058,2.002,1.961,1.890,1.827,1.762,1.724,1.690,1.652,1.615,1.595,1.560,1.528,1.498,1.457,1.438,1.404,1.385,1.351,1.331,1.304,1.287,1.268,1.239,1.206,1.182,1.166,1.158,1.151,1.142,1.139,1.122,1.106,1.099,1.098,1.104,1.109,1.110,1.136,1.123,1.131,1.139,1.132,1.123,1.114,1.097,1.100,1.085,1.076,1.067,1.058,1.039,1.033,1.010,0.990},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,1.000,1.000,88.000,122.000,94.000,73.000,60.000,54.000,54.000,56.000,63.000,66.000,67.000,67.000,69.000,70.000,72.000,74.000,75.000,77.000,76.000,78.000,78.000,79.000,81.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,78.000,78.000,79.000,80.000,76.000,76.000,78.000,78.000,77.000,76.000,74.000,71.000,72.000,75.000,73.000,70.000,69.000,69.000,68.000,64.000,67.000,69.000,70.000,72.000,74.000,73.000,69.000,68.000,71.000,71.000,70.000,66.000,58.000,51.000,39.000,32.000,32.000,42.000,49.000,49.000,52.000,52.000,50.000,51.000,51.000,41.000,43.000,46.000,43.000,42.000,38.000}
-64.611 LMS_LASER_2D_LEFT LMS1 ID=4251,time=1225719876.262654,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=248,Range=[181]{1.020,1.037,1.038,1.049,1.058,1.069,1.081,1.085,1.091,1.095,1.118,1.124,1.131,1.143,1.158,1.172,1.185,1.156,1.174,1.188,1.204,1.216,1.260,1.286,1.289,1.313,1.327,1.348,1.358,1.384,1.390,1.401,1.425,1.443,1.477,1.502,1.529,1.551,1.582,1.607,1.634,1.652,1.673,1.708,1.747,1.767,1.802,1.834,1.875,1.911,1.954,1.981,2.031,2.075,2.135,2.163,2.233,2.279,2.344,2.401,2.478,2.557,2.572,2.561,2.592,2.714,2.761,2.829,2.873,2.918,2.979,3.087,3.255,3.331,3.495,3.698,3.815,3.898,3.893,3.891,3.874,3.885,3.923,3.946,3.946,3.945,3.948,3.955,3.960,3.950,3.979,4.020,4.043,4.040,4.057,4.081,4.076,4.085,4.084,4.093,4.092,4.093,4.097,4.095,4.095,4.102,4.113,4.113,4.122,4.120,4.129,4.134,4.138,4.147,4.156,4.165,4.173,4.179,4.196,4.194,4.214,4.226,4.232,4.250,4.259,4.268,4.283,4.290,4.307,4.322,4.340,4.356,4.374,4.381,4.403,4.421,4.440,4.444,4.448,4.476,4.494,4.509,4.538,4.555,4.584,4.601,4.620,4.644,4.653,4.680,4.706,4.732,4.747,4.777,4.806,4.834,3.243,3.129,3.119,4.941,4.968,5.014,2.882,2.878,2.793,2.783,2.786,2.790,2.926,4.594,4.547,4.528,4.529,4.514,4.806,4.712,4.652,4.647,4.713,4.673,4.598},Reflectance=[181]{46.000,41.000,41.000,42.000,43.000,44.000,45.000,40.000,47.000,49.000,43.000,42.000,41.000,43.000,42.000,40.000,36.000,29.000,28.000,29.000,30.000,30.000,42.000,45.000,43.000,42.000,49.000,45.000,42.000,42.000,49.000,54.000,54.000,54.000,53.000,53.000,53.000,55.000,54.000,54.000,54.000,54.000,55.000,54.000,44.000,46.000,46.000,48.000,50.000,45.000,45.000,50.000,42.000,43.000,38.000,52.000,43.000,43.000,45.000,48.000,42.000,45.000,53.000,60.000,58.000,52.000,49.000,48.000,56.000,53.000,51.000,49.000,49.000,51.000,56.000,49.000,48.000,47.000,49.000,51.000,59.000,68.000,74.000,75.000,75.000,73.000,71.000,71.000,70.000,72.000,71.000,70.000,74.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,16.000,22.000,26.000,77.000,77.000,77.000,49.000,101.000,77.000,77.000,78.000,77.000,112.000,76.000,68.000,70.000,78.000,82.000,93.000,84.000,83.000,61.000,70.000,76.000,67.000}
-64.622 LMS_LASER_2D_RIGHT LMS2 ID=4124,time=1225719876.268178,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=213,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.258,-1.000,16.817,13.654,11.599,10.144,9.237,8.394,7.677,6.959,6.407,6.006,5.621,5.246,4.925,4.654,4.412,4.162,3.933,3.715,3.584,3.418,3.264,3.121,3.000,2.878,2.746,2.660,2.535,2.459,2.389,2.321,2.255,2.192,2.119,2.053,2.003,1.944,1.872,1.821,1.767,1.732,1.689,1.652,1.616,1.588,1.557,1.531,1.488,1.448,1.414,1.401,1.385,1.354,1.323,1.294,1.278,1.276,1.255,1.232,1.199,1.167,1.151,1.157,1.140,1.138,1.114,1.099,1.098,1.104,1.105,1.114,1.125,1.124,1.118,1.129,1.122,1.130,1.122,1.119,1.103,1.084,1.086,1.074,1.067,1.055,1.046,1.030,1.018,0.984},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,7.000,0.000,111.000,119.000,92.000,72.000,58.000,56.000,54.000,57.000,64.000,65.000,66.000,68.000,68.000,70.000,72.000,74.000,75.000,76.000,76.000,78.000,79.000,79.000,80.000,80.000,79.000,80.000,78.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,76.000,77.000,79.000,77.000,78.000,75.000,72.000,73.000,75.000,75.000,75.000,71.000,69.000,70.000,67.000,62.000,66.000,69.000,71.000,72.000,70.000,69.000,66.000,68.000,71.000,71.000,66.000,60.000,53.000,46.000,31.000,31.000,32.000,32.000,48.000,52.000,48.000,51.000,51.000,42.000,46.000,43.000,40.000,42.000,40.000,44.000,35.000}
-64.634 LMS_LASER_2D_RIGHT LMS2 ID=4125,time=1225719876.281515,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=214,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.251,-1.000,16.275,13.307,11.355,10.021,9.115,8.242,7.603,6.925,6.373,5.955,5.568,5.201,4.908,4.596,4.340,4.128,3.910,3.693,3.552,3.399,3.240,3.097,2.974,2.863,2.749,2.642,2.523,2.459,2.380,2.310,2.246,2.184,2.121,2.061,2.000,1.925,1.872,1.812,1.767,1.725,1.673,1.648,1.614,1.595,1.540,1.518,1.484,1.440,1.405,1.392,1.360,1.333,1.322,1.303,1.294,1.258,1.222,1.216,1.199,1.174,1.148,1.122,1.123,1.121,1.116,1.099,1.104,1.107,1.104,1.119,1.133,1.125,1.129,1.133,1.116,1.131,1.110,1.107,1.111,1.084,1.084,1.065,1.067,1.051,1.025,1.029,1.017,0.970},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,13.000,0.000,109.000,117.000,91.000,68.000,57.000,57.000,53.000,58.000,64.000,66.000,66.000,67.000,70.000,72.000,73.000,74.000,76.000,77.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,77.000,78.000,78.000,78.000,78.000,77.000,76.000,73.000,74.000,75.000,74.000,73.000,69.000,69.000,68.000,60.000,65.000,70.000,71.000,70.000,68.000,69.000,69.000,67.000,72.000,72.000,66.000,57.000,59.000,48.000,43.000,33.000,32.000,34.000,30.000,40.000,54.000,53.000,51.000,50.000,43.000,42.000,43.000,39.000,33.000,49.000,50.000,31.000}
-64.647 DESIRED_THRUST iJoystick 86.60237434
-64.647 DESIRED_RUDDER iJoystick 0
-64.635 LMS_LASER_2D_LEFT LMS1 ID=4252,time=1225719876.275996,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=249,Range=[181]{1.029,1.042,1.047,1.049,1.065,1.069,1.077,1.086,1.095,1.105,1.119,1.120,1.132,1.149,1.157,1.168,1.186,1.169,1.179,1.184,1.216,1.231,1.264,1.275,1.293,1.310,1.330,1.339,1.362,1.388,1.402,1.416,1.435,1.451,1.469,1.503,1.530,1.556,1.575,1.606,1.634,1.641,1.672,1.706,1.743,1.776,1.807,1.837,1.879,1.912,1.948,1.985,2.030,2.074,2.129,2.155,2.248,2.301,2.364,2.417,2.489,2.567,2.576,2.565,2.610,2.727,2.769,2.845,2.872,2.933,2.997,3.110,3.276,3.370,3.547,3.700,3.817,3.893,3.895,3.882,3.882,3.894,3.924,3.947,3.953,3.951,3.940,3.962,3.955,3.950,3.984,4.022,4.049,4.041,4.067,4.082,4.084,4.084,4.083,4.093,4.094,4.094,4.094,4.096,4.096,4.104,4.113,4.111,4.119,4.120,4.131,4.140,4.148,4.156,4.163,4.164,4.172,4.187,4.195,4.203,4.216,4.226,4.233,4.250,4.258,4.268,4.283,4.291,4.317,4.323,4.339,4.358,4.364,4.385,4.403,4.421,4.440,4.440,4.458,4.476,4.494,4.519,4.537,4.554,4.585,4.601,4.619,4.643,4.664,4.687,4.715,4.731,4.755,4.777,4.811,4.831,3.227,3.119,3.132,4.948,3.061,5.022,2.857,2.860,2.775,2.774,2.773,2.782,2.798,4.541,4.543,4.533,4.579,4.543,5.431,4.847,4.678,4.664,4.691,4.623,4.576},Reflectance=[181]{37.000,39.000,45.000,42.000,42.000,44.000,44.000,44.000,44.000,46.000,43.000,40.000,42.000,42.000,46.000,43.000,39.000,31.000,29.000,28.000,30.000,31.000,39.000,50.000,49.000,49.000,50.000,46.000,44.000,44.000,51.000,53.000,54.000,53.000,54.000,53.000,54.000,54.000,55.000,53.000,54.000,63.000,59.000,53.000,47.000,46.000,43.000,44.000,51.000,51.000,48.000,49.000,50.000,47.000,55.000,56.000,45.000,42.000,48.000,47.000,43.000,45.000,51.000,58.000,58.000,53.000,52.000,48.000,56.000,53.000,48.000,47.000,50.000,57.000,58.000,47.000,49.000,49.000,49.000,55.000,59.000,71.000,74.000,76.000,75.000,72.000,71.000,71.000,71.000,72.000,69.000,71.000,75.000,76.000,75.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,28.000,29.000,23.000,76.000,17.000,77.000,49.000,92.000,77.000,77.000,77.000,77.000,64.000,71.000,69.000,74.000,77.000,87.000,70.000,80.000,81.000,61.000,78.000,72.000,71.000}
-64.646 LMS_LASER_2D_RIGHT LMS2 ID=4126,time=1225719876.294851,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=215,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.793,-1.000,15.889,12.900,11.100,9.858,9.027,8.197,7.457,6.819,6.304,5.877,5.510,5.137,4.856,4.544,4.293,4.075,3.878,3.699,3.524,3.384,3.207,3.059,2.949,2.856,2.740,2.634,2.511,2.438,2.371,2.291,2.227,2.165,2.113,2.044,1.985,1.925,1.864,1.803,1.758,1.723,1.671,1.656,1.622,1.579,1.539,1.515,1.484,1.430,1.395,1.385,1.363,1.354,1.323,1.306,1.275,1.235,1.216,1.210,1.199,1.172,1.139,1.141,1.133,1.123,1.123,1.105,1.096,1.099,1.104,1.105,1.125,1.121,1.120,1.118,1.101,1.093,1.122,1.110,1.104,1.090,1.084,1.068,1.053,1.048,1.039,1.027,1.009,0.984},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,29.000,0.000,115.000,117.000,88.000,67.000,56.000,56.000,56.000,58.000,64.000,66.000,67.000,68.000,71.000,72.000,73.000,74.000,77.000,77.000,78.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,77.000,73.000,77.000,78.000,78.000,77.000,78.000,77.000,72.000,72.000,76.000,75.000,75.000,71.000,61.000,59.000,61.000,70.000,73.000,71.000,66.000,67.000,71.000,72.000,70.000,70.000,68.000,67.000,61.000,59.000,52.000,43.000,35.000,31.000,31.000,29.000,28.000,40.000,47.000,48.000,46.000,43.000,41.000,40.000,47.000,40.000,39.000,47.000,36.000}
-64.646 LMS_LASER_2D_LEFT LMS1 ID=4253,time=1225719876.289337,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=250,Range=[181]{1.034,1.034,1.054,1.055,1.065,1.070,1.082,1.090,1.098,1.108,1.111,1.124,1.131,1.149,1.156,1.171,1.190,1.174,1.185,1.209,1.222,1.255,1.274,1.287,1.289,1.312,1.325,1.348,1.365,1.383,1.401,1.416,1.434,1.460,1.477,1.510,1.525,1.564,1.584,1.607,1.626,1.632,1.661,1.714,1.756,1.788,1.809,1.846,1.877,1.920,1.946,1.996,2.038,2.099,2.122,2.149,2.243,2.309,2.370,2.428,2.508,2.567,2.570,2.569,2.625,2.730,2.769,2.840,2.873,2.959,3.015,3.148,3.281,3.386,3.582,3.719,3.833,3.899,3.898,3.893,3.881,3.900,3.933,3.947,3.943,3.952,3.948,3.968,3.952,3.962,3.993,4.026,4.048,4.040,4.067,4.074,4.084,4.085,4.084,4.094,4.093,4.092,4.096,4.096,4.105,4.104,4.113,4.120,4.121,4.130,4.131,4.141,4.147,4.157,4.164,4.166,4.179,4.188,4.193,4.203,4.216,4.225,4.239,4.249,4.268,4.268,4.283,4.299,4.312,4.329,4.340,4.347,4.365,4.383,4.401,4.420,4.439,4.451,4.458,4.484,4.503,4.517,4.547,4.567,4.583,4.601,4.629,4.651,4.662,4.696,4.715,4.738,4.763,4.785,4.810,4.838,3.209,3.139,3.127,3.044,3.064,5.020,2.843,2.783,2.759,2.759,2.764,2.780,2.907,4.519,4.508,4.528,4.449,4.825,5.417,4.800,4.681,4.664,4.694,4.600,4.504},Reflectance=[181]{39.000,39.000,41.000,37.000,42.000,44.000,42.000,45.000,45.000,42.000,39.000,42.000,38.000,42.000,46.000,40.000,38.000,30.000,29.000,32.000,31.000,39.000,40.000,47.000,52.000,50.000,52.000,50.000,50.000,50.000,54.000,53.000,54.000,54.000,53.000,53.000,56.000,53.000,55.000,54.000,58.000,64.000,58.000,53.000,44.000,42.000,44.000,46.000,50.000,54.000,54.000,50.000,46.000,42.000,61.000,62.000,48.000,45.000,45.000,48.000,44.000,47.000,52.000,60.000,56.000,55.000,56.000,49.000,56.000,50.000,47.000,48.000,52.000,56.000,54.000,51.000,48.000,48.000,47.000,49.000,58.000,72.000,74.000,76.000,75.000,72.000,71.000,70.000,70.000,73.000,70.000,72.000,75.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,77.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,76.000,32.000,29.000,20.000,31.000,40.000,77.000,54.000,77.000,78.000,78.000,77.000,76.000,110.000,70.000,72.000,78.000,68.000,87.000,68.000,76.000,76.000,63.000,77.000,70.000,71.000}
-64.662 LMS_LASER_2D_LEFT LMS1 ID=4254,time=1225719876.302681,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=251,Range=[181]{1.033,1.043,1.049,1.051,1.072,1.071,1.084,1.092,1.101,1.106,1.117,1.124,1.130,1.147,1.164,1.179,1.192,1.168,1.217,1.229,1.246,1.256,1.274,1.282,1.295,1.313,1.332,1.355,1.370,1.383,1.401,1.409,1.435,1.459,1.486,1.512,1.529,1.564,1.582,1.610,1.623,1.641,1.688,1.722,1.758,1.790,1.821,1.855,1.885,1.913,1.954,1.995,2.054,2.104,2.123,2.157,2.265,2.328,2.380,2.446,2.522,2.571,2.576,2.576,2.662,2.732,2.798,2.858,2.898,2.981,3.037,3.195,3.295,3.435,3.628,3.746,3.861,3.899,3.891,3.892,3.887,3.904,3.933,3.950,3.949,3.951,3.947,3.968,3.952,3.961,3.997,4.039,4.050,4.048,4.076,4.082,4.083,4.084,4.082,4.094,4.092,4.092,4.101,4.097,4.104,4.111,4.112,4.119,4.119,4.136,4.140,4.139,4.147,4.154,4.164,4.172,4.180,4.186,4.193,4.205,4.216,4.225,4.240,4.257,4.267,4.277,4.284,4.300,4.312,4.330,4.346,4.356,4.375,4.385,4.401,4.420,4.439,4.448,4.469,4.485,4.501,4.529,4.546,4.565,4.583,4.609,4.627,4.652,4.669,4.697,4.724,4.738,4.762,4.791,4.820,3.234,3.365,3.154,3.093,3.168,3.189,5.019,2.813,2.765,2.740,2.740,2.754,2.764,2.901,4.537,4.469,4.451,4.431,4.803,4.852,4.719,4.845,4.731,4.671,4.596,4.450},Reflectance=[181]{38.000,39.000,38.000,40.000,38.000,40.000,43.000,43.000,43.000,41.000,42.000,45.000,46.000,46.000,46.000,37.000,36.000,29.000,34.000,35.000,39.000,40.000,44.000,49.000,50.000,51.000,47.000,46.000,52.000,54.000,54.000,54.000,54.000,53.000,54.000,50.000,53.000,53.000,54.000,55.000,64.000,61.000,54.000,52.000,49.000,43.000,45.000,49.000,54.000,55.000,54.000,49.000,46.000,44.000,63.000,61.000,44.000,45.000,46.000,44.000,42.000,49.000,55.000,59.000,52.000,56.000,50.000,46.000,56.000,48.000,50.000,49.000,51.000,54.000,47.000,52.000,49.000,48.000,48.000,48.000,62.000,73.000,74.000,74.000,74.000,72.000,71.000,70.000,70.000,72.000,71.000,73.000,76.000,75.000,75.000,77.000,77.000,78.000,77.000,78.000,77.000,77.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,79.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,76.000,24.000,117.000,31.000,28.000,113.000,116.000,76.000,60.000,77.000,78.000,78.000,76.000,74.000,106.000,73.000,77.000,74.000,69.000,85.000,80.000,74.000,63.000,75.000,78.000,69.000,69.000}
-64.662 LMS_LASER_2D_RIGHT LMS2 ID=4127,time=1225719876.308189,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=216,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.537,18.581,15.413,12.551,10.849,9.676,8.867,8.031,7.314,6.732,6.225,5.767,5.433,5.075,4.801,4.491,4.256,4.020,3.842,3.683,3.508,3.353,3.167,3.049,2.923,2.821,2.706,2.602,2.491,2.424,2.353,2.283,2.218,2.157,2.086,2.027,1.967,1.907,1.851,1.794,1.759,1.724,1.677,1.651,1.605,1.578,1.544,1.507,1.469,1.423,1.396,1.381,1.372,1.346,1.304,1.257,1.225,1.217,1.216,1.212,1.199,1.173,1.149,1.142,1.133,1.123,1.114,1.098,1.097,1.096,1.107,1.116,1.120,1.129,1.114,1.098,1.092,1.095,1.098,1.096,1.069,1.067,1.069,1.058,1.060,1.038,1.029,1.025,1.004,0.978},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,29.000,43.000,109.000,112.000,82.000,65.000,55.000,56.000,57.000,58.000,65.000,66.000,69.000,69.000,71.000,72.000,74.000,75.000,76.000,77.000,78.000,78.000,79.000,79.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,79.000,79.000,79.000,76.000,78.000,78.000,78.000,79.000,78.000,77.000,73.000,73.000,77.000,77.000,75.000,69.000,64.000,70.000,71.000,76.000,74.000,69.000,68.000,71.000,73.000,72.000,69.000,68.000,70.000,69.000,66.000,57.000,50.000,44.000,35.000,32.000,29.000,28.000,29.000,31.000,34.000,28.000,30.000,35.000,33.000,41.000,52.000,49.000,43.000,48.000,35.000}
-64.663 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.6045,20.4861,-0.9389},Vel=[3x1]{-0.7423,-0.5434,-4.8718},Raw=[2x1]{23.0765,-0.9389},time=1225719876.31079339981079,Speed=0.91994976782220,Pitch=0.02692024480606,Roll=0.01794682987071,PitchDot=-0.06057055081364,RollDot=0.00085247441886
-64.663 ODOMETRY_POSE iPlatform Pose=[3x1]{6.6045,20.4861,-0.9387},Vel=[3x1]{-0.7423,-0.5434,1.4116},Raw=[2x1]{23.0765,-0.9389},time=1225719876.3108,Speed=0.9199,Pitch=0.0014,Roll=0.0323,PitchDot=-0.0088,RollDot=0.0599
-64.671 DESIRED_THRUST iJoystick 86.60237434
-64.671 DESIRED_RUDDER iJoystick 0
-64.675 DB_CLIENTS MOOSDB#1 LMS2,LMS1,iCameraLadybug,iGPS,pLogStereo,iCameraBumbleBee,uWatchdog,iJoystick,pNav,pLogger,iRemote,iRelayBox,iPlatform,Antler{lisa2},Antler{lisa3},Antler{Monarch},Antler{lisa4},DBWebServer,
-64.674 LMS_LASER_2D_RIGHT LMS2 ID=4128,time=1225719876.321526,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=217,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.793,17.488,14.648,12.138,10.462,9.497,8.619,7.838,7.197,6.642,6.127,5.706,5.346,5.016,4.748,4.438,4.194,3.985,3.803,3.622,3.463,3.315,3.147,3.013,2.890,2.795,2.678,2.568,2.486,2.433,2.324,2.264,2.201,2.131,2.079,2.010,1.933,1.881,1.825,1.783,1.743,1.717,1.670,1.621,1.595,1.571,1.539,1.497,1.467,1.437,1.410,1.383,1.365,1.335,1.303,1.259,1.242,1.234,1.236,1.226,1.205,1.174,1.158,1.142,1.124,1.116,1.122,1.106,1.098,1.095,1.117,1.125,1.120,1.124,1.126,1.095,1.086,1.095,1.112,1.102,1.063,1.071,1.065,1.026,1.042,1.038,1.026,1.012,0.993,0.991},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,67.000,114.000,103.000,81.000,60.000,57.000,54.000,58.000,63.000,66.000,67.000,69.000,69.000,71.000,72.000,74.000,75.000,77.000,77.000,78.000,78.000,78.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,80.000,80.000,79.000,78.000,78.000,79.000,77.000,78.000,77.000,76.000,75.000,78.000,78.000,74.000,68.000,67.000,70.000,71.000,74.000,71.000,66.000,69.000,72.000,74.000,72.000,72.000,67.000,71.000,69.000,65.000,54.000,43.000,37.000,34.000,41.000,29.000,28.000,29.000,45.000,48.000,28.000,31.000,34.000,27.000,31.000,40.000,51.000,52.000,51.000,43.000}
-64.674 LMS_LASER_2D_LEFT LMS1 ID=4255,time=1225719876.316023,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=252,Range=[181]{1.038,1.043,1.049,1.056,1.070,1.075,1.082,1.089,1.101,1.114,1.123,1.134,1.143,1.164,1.168,1.158,1.206,1.199,1.211,1.236,1.249,1.263,1.268,1.284,1.301,1.322,1.330,1.358,1.374,1.391,1.410,1.424,1.442,1.468,1.485,1.511,1.540,1.564,1.595,1.621,1.623,1.651,1.699,1.729,1.765,1.801,1.838,1.868,1.894,1.928,1.963,2.013,2.057,2.097,2.132,2.171,2.271,2.338,2.400,2.464,2.535,2.574,2.566,2.588,2.701,2.748,2.814,2.862,2.912,2.997,3.067,3.225,3.346,3.515,3.665,3.769,3.879,3.900,3.892,3.896,3.887,3.915,3.942,3.950,3.947,3.952,3.954,3.968,3.946,3.975,4.015,4.042,4.049,4.045,4.087,4.083,4.076,4.093,4.092,4.095,4.094,4.093,4.102,4.096,4.113,4.120,4.119,4.118,4.129,4.137,4.148,4.148,4.147,4.165,4.173,4.173,4.180,4.187,4.203,4.215,4.224,4.232,4.248,4.256,4.276,4.276,4.291,4.300,4.320,4.329,4.347,4.355,4.375,4.384,4.400,4.421,4.442,4.449,4.476,4.494,4.511,4.528,4.546,4.567,4.592,4.608,4.636,4.652,4.677,4.707,4.724,4.747,4.776,4.801,4.829,3.219,3.294,3.164,3.211,3.044,3.206,5.025,2.900,2.741,2.729,2.724,2.732,2.755,2.914,4.574,4.499,4.410,4.633,4.793,4.727,4.696,5.048,4.836,4.622,4.502,4.504},Reflectance=[181]{37.000,36.000,34.000,42.000,40.000,47.000,47.000,41.000,43.000,45.000,45.000,43.000,43.000,40.000,36.000,30.000,35.000,34.000,33.000,38.000,41.000,43.000,46.000,50.000,49.000,51.000,46.000,47.000,50.000,53.000,51.000,53.000,53.000,53.000,53.000,53.000,55.000,53.000,56.000,56.000,64.000,57.000,54.000,52.000,52.000,49.000,41.000,45.000,54.000,54.000,54.000,46.000,54.000,53.000,62.000,59.000,44.000,48.000,43.000,44.000,44.000,50.000,54.000,60.000,53.000,55.000,49.000,48.000,55.000,48.000,47.000,47.000,46.000,53.000,50.000,51.000,50.000,48.000,48.000,50.000,64.000,74.000,74.000,74.000,73.000,72.000,71.000,70.000,71.000,72.000,71.000,74.000,75.000,75.000,76.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,76.000,76.000,76.000,38.000,108.000,35.000,113.000,75.000,116.000,75.000,124.000,78.000,77.000,76.000,75.000,74.000,108.000,80.000,77.000,70.000,72.000,85.000,74.000,70.000,59.000,73.000,74.000,71.000,74.000}
-64.686 LMS_LASER_2D_LEFT LMS1 ID=4256,time=1225719876.329363,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=253,Range=[181]{1.042,1.050,1.060,1.067,1.067,1.081,1.086,1.098,1.108,1.110,1.127,1.142,1.147,1.163,1.176,1.155,1.195,1.215,1.217,1.238,1.253,1.271,1.281,1.293,1.306,1.311,1.347,1.370,1.379,1.398,1.414,1.433,1.460,1.468,1.494,1.514,1.549,1.571,1.598,1.620,1.639,1.677,1.708,1.742,1.765,1.807,1.838,1.868,1.911,1.920,1.988,2.030,2.060,2.080,2.148,2.183,2.293,2.349,2.407,2.486,2.567,2.577,2.564,2.596,2.704,2.741,2.818,2.885,2.933,3.029,3.120,3.259,3.389,3.546,3.678,3.781,3.896,3.899,3.900,3.894,3.884,3.925,3.942,3.949,3.948,3.953,3.960,3.963,3.950,3.985,4.023,4.044,4.040,4.058,4.089,4.083,4.084,4.084,4.093,4.094,4.093,4.101,4.104,4.103,4.108,4.119,4.117,4.118,4.128,4.139,4.140,4.148,4.155,4.163,4.164,4.172,4.188,4.193,4.203,4.207,4.224,4.241,4.250,4.255,4.275,4.286,4.291,4.311,4.319,4.338,4.346,4.366,4.374,4.394,4.401,4.421,4.439,4.458,4.476,4.494,4.519,4.539,4.555,4.575,4.590,4.617,4.643,4.653,4.679,4.709,4.731,4.756,4.786,4.809,4.829,3.340,3.285,3.163,3.165,3.046,3.088,5.039,2.868,2.728,2.715,2.704,2.711,2.737,2.791,4.572,4.427,4.496,4.708,4.742,4.701,4.711,5.077,4.762,4.609,4.436,4.602},Reflectance=[181]{38.000,38.000,39.000,43.000,43.000,45.000,44.000,41.000,42.000,48.000,39.000,36.000,40.000,40.000,36.000,28.000,44.000,40.000,34.000,39.000,43.000,43.000,43.000,50.000,51.000,53.000,50.000,43.000,48.000,41.000,49.000,53.000,54.000,53.000,53.000,55.000,55.000,56.000,54.000,55.000,60.000,52.000,54.000,54.000,52.000,48.000,46.000,46.000,54.000,54.000,53.000,45.000,59.000,57.000,57.000,57.000,46.000,49.000,46.000,45.000,45.000,51.000,58.000,59.000,55.000,59.000,51.000,50.000,56.000,49.000,47.000,47.000,50.000,50.000,49.000,52.000,50.000,48.000,48.000,49.000,68.000,74.000,74.000,74.000,74.000,73.000,70.000,68.000,72.000,70.000,71.000,74.000,76.000,75.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,76.000,76.000,117.000,108.000,38.000,110.000,74.000,49.000,74.000,115.000,77.000,76.000,75.000,75.000,74.000,46.000,81.000,75.000,62.000,71.000,82.000,72.000,72.000,75.000,79.000,68.000,67.000,73.000}
-64.686 LMS_LASER_2D_RIGHT LMS2 ID=4129,time=1225719876.334862,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=218,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,17.008,13.896,11.698,10.197,9.313,8.434,7.702,7.031,6.503,5.972,5.628,5.264,4.954,4.639,4.375,4.134,3.925,3.753,3.575,3.448,3.281,3.124,2.977,2.860,2.767,2.643,2.550,2.469,2.407,2.309,2.246,2.174,2.122,2.062,1.993,1.924,1.863,1.806,1.770,1.743,1.719,1.662,1.628,1.586,1.558,1.521,1.475,1.449,1.431,1.396,1.372,1.351,1.338,1.318,1.286,1.269,1.253,1.226,1.215,1.204,1.188,1.157,1.148,1.138,1.116,1.106,1.097,1.098,1.095,1.119,1.123,1.121,1.117,1.113,1.113,1.113,1.117,1.103,1.099,1.080,1.086,1.078,1.065,1.048,1.010,1.025,1.007,0.998,0.986},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,112.000,119.000,94.000,77.000,57.000,58.000,53.000,60.000,64.000,66.000,65.000,68.000,69.000,72.000,71.000,74.000,75.000,75.000,77.000,80.000,78.000,80.000,81.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,75.000,77.000,80.000,80.000,79.000,77.000,75.000,78.000,77.000,74.000,73.000,72.000,73.000,74.000,73.000,67.000,63.000,68.000,70.000,73.000,72.000,68.000,63.000,65.000,70.000,69.000,66.000,71.000,70.000,68.000,69.000,64.000,51.000,38.000,40.000,36.000,34.000,34.000,34.000,43.000,51.000,47.000,34.000,42.000,45.000,41.000,34.000,28.000,41.000,46.000,46.000,39.000}
-64.695 DESIRED_THRUST iJoystick 86.60237434
-64.695 DESIRED_RUDDER iJoystick 0
-64.695 DESIRED_RUDDER iRemote 0
-64.695 DESIRED_THRUST iRemote 0
-64.695 DESIRED_ELEVATOR iRemote 0
-64.699 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.6196,20.4972,-0.9375},Vel=[3x1]{-0.7369,-0.5409,-2.9487},Raw=[2x1]{23.0953,-0.9375},time=1225719876.34652757644653,Speed=0.91410881691539,Pitch=0.02467689107222,Roll=0.02019018360455,PitchDot=-0.06730061201516,RollDot=0.00125627809095
-64.699 ODOMETRY_POSE iPlatform Pose=[3x1]{6.6196,20.4972,-0.9372},Vel=[3x1]{-0.7369,-0.5409,-2.9483},Raw=[2x1]{23.0953,-0.9375},time=1225719876.3465,Speed=0.9141,Pitch=-0.0017,Roll=0.0318,PitchDot=0.0658,RollDot=-0.0142
-64.327 RELAYBOX_STATUS iRelayBox LADYBUG is OFF,LMS1 is ON,LMS2 is ON,P10 is OFF,P11 is OFF,P12 is OFF,P13 is OFF,P14 is OFF,P15 is OFF,P16 is OFF,P5 is OFF,P6 is OFF,P7 is OFF,P8 is OFF,P9 is OFF,PANTILT is ON,
-64.699 LMS_LASER_2D_LEFT LMS1 ID=4257,time=1225719876.342704,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=254,Range=[181]{1.038,1.045,1.063,1.069,1.071,1.084,1.090,1.104,1.105,1.116,1.122,1.131,1.149,1.164,1.154,1.162,1.189,1.199,1.225,1.245,1.255,1.269,1.282,1.291,1.315,1.327,1.345,1.370,1.388,1.396,1.425,1.426,1.451,1.477,1.497,1.523,1.548,1.577,1.603,1.627,1.644,1.681,1.711,1.747,1.783,1.814,1.843,1.883,1.914,1.929,1.991,2.043,2.063,2.103,2.178,2.238,2.303,2.371,2.429,2.502,2.574,2.579,2.574,2.622,2.719,2.763,2.820,2.894,2.976,3.049,3.153,3.306,3.434,3.586,3.704,3.815,3.906,3.898,3.890,3.900,3.904,3.934,3.943,3.958,3.957,3.955,3.960,3.961,3.959,3.997,4.026,4.057,4.051,4.067,4.088,4.083,4.093,4.093,4.094,4.094,4.101,4.103,4.102,4.108,4.117,4.117,4.125,4.125,4.138,4.146,4.149,4.147,4.155,4.164,4.171,4.181,4.187,4.193,4.205,4.215,4.224,4.240,4.249,4.266,4.283,4.284,4.299,4.311,4.329,4.346,4.348,4.365,4.385,4.392,4.412,4.430,4.448,4.465,4.484,4.494,4.519,4.545,4.556,4.582,4.598,4.614,4.638,4.669,4.690,4.715,4.739,4.764,4.785,4.810,4.840,3.331,3.279,3.155,3.175,3.050,3.100,2.809,2.830,2.714,2.685,2.682,2.682,2.706,2.703,4.463,4.392,4.550,4.720,4.658,4.687,4.745,5.106,4.698,4.557,4.452,4.671},Reflectance=[181]{41.000,37.000,40.000,44.000,46.000,43.000,45.000,40.000,46.000,47.000,46.000,41.000,42.000,35.000,31.000,29.000,53.000,50.000,42.000,43.000,44.000,42.000,44.000,49.000,48.000,53.000,49.000,48.000,48.000,32.000,46.000,54.000,53.000,53.000,55.000,59.000,58.000,56.000,56.000,55.000,54.000,54.000,55.000,52.000,49.000,54.000,48.000,41.000,52.000,54.000,48.000,48.000,61.000,56.000,55.000,45.000,48.000,46.000,49.000,45.000,46.000,52.000,58.000,59.000,50.000,63.000,56.000,50.000,50.000,51.000,50.000,52.000,53.000,48.000,49.000,48.000,51.000,47.000,51.000,55.000,71.000,75.000,75.000,74.000,74.000,73.000,70.000,70.000,72.000,71.000,72.000,75.000,76.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,78.000,78.000,78.000,78.000,77.000,76.000,76.000,77.000,117.000,103.000,31.000,112.000,70.000,30.000,32.000,104.000,75.000,75.000,74.000,74.000,73.000,32.000,67.000,73.000,64.000,77.000,77.000,71.000,72.000,76.000,83.000,68.000,69.000,78.000}
-64.711 LMS_LASER_2D_LEFT LMS1 ID=4258,time=1225719876.356043,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=255,Range=[181]{1.041,1.050,1.067,1.068,1.081,1.090,1.097,1.101,1.100,1.124,1.134,1.146,1.149,1.174,1.190,1.194,1.184,1.197,1.221,1.241,1.262,1.276,1.286,1.298,1.311,1.330,1.349,1.363,1.389,1.405,1.422,1.435,1.459,1.480,1.505,1.524,1.557,1.584,1.608,1.634,1.670,1.685,1.724,1.750,1.792,1.820,1.859,1.893,1.912,1.955,2.005,2.035,2.055,2.127,2.191,2.270,2.330,2.389,2.450,2.502,2.577,2.586,2.582,2.644,2.734,2.771,2.847,2.913,2.973,3.068,3.194,3.327,3.461,3.614,3.719,3.851,3.911,3.897,3.899,3.898,3.912,3.936,3.951,3.951,3.950,3.953,3.964,3.955,3.959,4.005,4.039,4.058,4.049,4.076,4.092,4.083,4.094,4.093,4.091,4.100,4.102,4.103,4.109,4.114,4.116,4.117,4.125,4.131,4.137,4.136,4.147,4.155,4.162,4.163,4.174,4.181,4.186,4.202,4.207,4.216,4.231,4.240,4.248,4.264,4.283,4.293,4.300,4.320,4.336,4.347,4.357,4.374,4.385,4.401,4.421,4.430,4.451,4.464,4.485,4.502,4.529,4.546,4.567,4.582,4.606,4.631,4.648,4.667,4.697,4.724,4.738,4.762,4.791,4.821,4.853,3.321,3.283,3.170,3.193,3.170,5.022,2.796,2.735,2.685,2.656,2.637,2.631,2.597,2.566,2.560,2.563,4.803,4.713,4.627,4.697,4.877,4.870,4.650,4.523,4.434,4.974},Reflectance=[181]{43.000,39.000,38.000,43.000,45.000,45.000,45.000,39.000,47.000,45.000,43.000,44.000,45.000,42.000,37.000,39.000,54.000,53.000,49.000,45.000,43.000,41.000,45.000,48.000,50.000,50.000,51.000,53.000,52.000,32.000,49.000,54.000,53.000,55.000,54.000,59.000,58.000,59.000,58.000,58.000,54.000,56.000,54.000,54.000,52.000,49.000,46.000,50.000,54.000,54.000,46.000,56.000,62.000,55.000,49.000,43.000,48.000,42.000,45.000,50.000,47.000,51.000,57.000,56.000,52.000,64.000,52.000,55.000,55.000,52.000,48.000,49.000,53.000,48.000,47.000,49.000,53.000,47.000,48.000,58.000,73.000,75.000,75.000,75.000,74.000,73.000,69.000,71.000,72.000,71.000,73.000,75.000,75.000,75.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,76.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,76.000,77.000,76.000,116.000,107.000,21.000,112.000,92.000,75.000,52.000,79.000,75.000,74.000,74.000,75.000,71.000,50.000,32.000,19.000,74.000,81.000,75.000,73.000,75.000,91.000,75.000,62.000,72.000,78.000}
-64.711 LMS_LASER_2D_RIGHT LMS2 ID=4130,time=1225719876.348209,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=219,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.860,-1.000,16.270,13.281,11.184,9.945,9.064,8.214,7.544,6.887,6.374,5.858,5.552,5.183,4.881,4.579,4.312,4.093,3.882,3.700,3.560,3.410,3.241,3.106,2.940,2.845,2.719,2.642,2.511,2.442,2.364,2.291,2.227,2.156,2.103,2.053,1.961,1.908,1.860,1.797,1.756,1.726,1.701,1.660,1.620,1.581,1.536,1.501,1.478,1.451,1.423,1.394,1.370,1.359,1.330,1.302,1.279,1.251,1.240,1.224,1.214,1.196,1.165,1.158,1.141,1.131,1.116,1.098,1.099,1.087,1.101,1.124,1.126,1.115,1.119,1.120,1.121,1.123,1.101,1.093,1.098,1.095,1.072,1.063,1.055,1.043,1.005,1.020,1.001,0.991,0.968},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,0.000,105.000,118.000,91.000,68.000,57.000,56.000,55.000,61.000,65.000,66.000,67.000,68.000,69.000,71.000,72.000,74.000,75.000,74.000,77.000,79.000,77.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,75.000,78.000,80.000,80.000,78.000,78.000,77.000,73.000,74.000,75.000,74.000,73.000,71.000,72.000,71.000,68.000,67.000,72.000,71.000,67.000,67.000,67.000,65.000,68.000,71.000,72.000,68.000,71.000,71.000,71.000,66.000,58.000,46.000,47.000,46.000,39.000,48.000,45.000,40.000,54.000,54.000,46.000,44.000,49.000,49.000,49.000,36.000,29.000,45.000,43.000,34.000,32.000}
-64.719 DESIRED_THRUST iJoystick 86.60237434
-64.719 DESIRED_RUDDER iJoystick 0
-64.722 LMS_LASER_2D_RIGHT LMS2 ID=4131,time=1225719876.361553,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=220,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.439,19.524,15.694,12.763,10.778,9.712,8.880,8.039,7.427,6.793,6.154,5.757,5.458,5.112,4.808,4.517,4.256,4.046,3.849,3.687,3.535,3.377,3.212,3.071,2.915,2.822,2.707,2.605,2.494,2.416,2.361,2.275,2.209,2.157,2.095,2.036,1.950,1.890,1.855,1.782,1.749,1.725,1.690,1.651,1.614,1.569,1.536,1.511,1.472,1.443,1.410,1.386,1.366,1.349,1.313,1.293,1.278,1.258,1.248,1.230,1.207,1.190,1.166,1.150,1.133,1.124,1.107,1.098,1.089,1.094,1.096,1.112,1.119,1.122,1.117,1.117,1.117,1.115,1.097,1.098,1.093,1.084,1.068,1.058,1.057,1.030,0.996,1.009,1.000,0.987,0.949},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,49.000,22.000,105.000,114.000,89.000,65.000,57.000,56.000,58.000,62.000,67.000,65.000,67.000,69.000,70.000,70.000,73.000,74.000,75.000,75.000,78.000,78.000,79.000,80.000,80.000,80.000,81.000,80.000,77.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,76.000,79.000,80.000,80.000,78.000,78.000,75.000,73.000,74.000,75.000,75.000,75.000,72.000,66.000,69.000,70.000,66.000,69.000,67.000,64.000,64.000,69.000,68.000,69.000,71.000,72.000,72.000,72.000,71.000,69.000,64.000,56.000,42.000,43.000,40.000,36.000,41.000,41.000,46.000,56.000,53.000,47.000,50.000,51.000,50.000,47.000,32.000,27.000,41.000,47.000,32.000,31.000}
-64.735 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.6493,20.5190,-0.9343},Vel=[3x1]{-0.7421,-0.5486,-0.3846},Raw=[2x1]{23.1322,-0.9343},time=1225719876.38265156745911,Speed=0.92287024327561,Pitch=0.02467689107222,Roll=0.02692024480606,PitchDot=-0.03589365974142,RollDot=0.00100950918023
-64.735 ODOMETRY_POSE iPlatform Pose=[3x1]{6.6493,20.5190,-0.9338},Vel=[3x1]{-0.7421,-0.5486,-0.3848},Raw=[2x1]{23.1322,-0.9343},time=1225719876.3827,Speed=0.9229,Pitch=-0.0070,Roll=0.0358,PitchDot=-0.0336,RollDot=-0.0125
-64.722 LMS_LASER_2D_LEFT LMS1 ID=4259,time=1225719876.369380,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=0,Range=[181]{1.040,1.058,1.058,1.064,1.077,1.082,1.094,1.102,1.107,1.118,1.141,1.149,1.157,1.169,1.178,1.204,1.190,1.198,1.214,1.250,1.260,1.270,1.285,1.296,1.317,1.331,1.356,1.372,1.394,1.423,1.431,1.452,1.468,1.486,1.509,1.532,1.564,1.594,1.611,1.639,1.673,1.698,1.732,1.769,1.787,1.830,1.868,1.886,1.912,1.967,2.009,2.030,2.062,2.151,2.211,2.277,2.333,2.392,2.464,2.530,2.578,2.576,2.592,2.701,2.742,2.789,2.873,2.951,3.009,3.094,3.231,3.340,3.502,3.624,3.740,3.871,3.910,3.900,3.899,3.887,3.915,3.945,3.953,3.958,3.956,3.959,3.964,3.956,3.976,4.011,4.040,4.059,4.057,4.086,4.090,4.094,4.092,4.091,4.098,4.101,4.104,4.103,4.108,4.117,4.109,4.117,4.129,4.129,4.140,4.139,4.149,4.155,4.164,4.163,4.171,4.181,4.194,4.204,4.215,4.224,4.232,4.241,4.257,4.274,4.282,4.291,4.308,4.330,4.337,4.354,4.365,4.376,4.392,4.401,4.419,4.439,4.448,4.475,4.494,4.511,4.528,4.547,4.565,4.590,4.606,4.630,4.650,4.679,4.696,4.723,4.746,4.771,4.803,4.831,4.855,3.317,3.294,4.938,3.220,3.098,5.026,2.758,2.686,2.638,2.603,2.576,2.561,2.549,2.634,2.662,2.565,2.578,4.685,4.719,4.740,4.866,4.753,4.704,4.500,4.405,5.012},Reflectance=[181]{42.000,43.000,43.000,45.000,44.000,42.000,44.000,43.000,46.000,43.000,42.000,45.000,45.000,43.000,44.000,36.000,53.000,53.000,53.000,45.000,47.000,47.000,50.000,51.000,49.000,51.000,50.000,53.000,43.000,37.000,52.000,54.000,53.000,54.000,56.000,55.000,57.000,55.000,55.000,56.000,51.000,54.000,54.000,54.000,54.000,45.000,46.000,54.000,54.000,49.000,48.000,63.000,61.000,54.000,50.000,47.000,44.000,48.000,44.000,46.000,48.000,55.000,58.000,50.000,52.000,61.000,49.000,53.000,53.000,52.000,49.000,51.000,47.000,49.000,46.000,50.000,52.000,48.000,48.000,63.000,74.000,75.000,75.000,74.000,74.000,72.000,69.000,71.000,72.000,70.000,73.000,76.000,75.000,76.000,77.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,113.000,108.000,76.000,113.000,50.000,76.000,59.000,75.000,75.000,75.000,75.000,76.000,75.000,100.000,109.000,50.000,19.000,81.000,81.000,75.000,84.000,92.000,77.000,67.000,63.000,79.000}
-64.734 LMS_LASER_2D_LEFT LMS1 ID=4260,time=1225719876.382715,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=1,Range=[181]{1.050,1.059,1.058,1.071,1.085,1.086,1.094,1.107,1.112,1.118,1.130,1.151,1.163,1.176,1.186,1.201,1.205,1.199,1.214,1.244,1.264,1.278,1.285,1.302,1.320,1.335,1.365,1.380,1.403,1.422,1.429,1.451,1.468,1.487,1.514,1.551,1.563,1.596,1.623,1.654,1.688,1.707,1.732,1.782,1.805,1.837,1.871,1.888,1.941,1.974,2.018,2.046,2.092,2.169,2.227,2.268,2.332,2.408,2.482,2.538,2.583,2.575,2.586,2.704,2.750,2.814,2.894,2.955,3.024,3.132,3.263,3.376,3.525,3.647,3.768,3.882,3.905,3.901,3.901,3.887,3.925,3.946,3.954,3.957,3.956,3.963,3.969,3.950,3.980,4.021,4.054,4.058,4.055,4.088,4.091,4.093,4.093,4.100,4.099,4.108,4.103,4.103,4.108,4.110,4.118,4.125,4.120,4.130,4.138,4.147,4.148,4.157,4.163,4.165,4.181,4.188,4.194,4.205,4.216,4.224,4.232,4.250,4.257,4.275,4.283,4.301,4.310,4.321,4.338,4.356,4.366,4.385,4.392,4.410,4.428,4.439,4.458,4.476,4.493,4.521,4.537,4.557,4.573,4.589,4.616,4.639,4.659,4.686,4.705,4.732,4.754,4.777,4.810,4.831,4.866,3.323,3.306,3.262,3.245,3.118,5.035,2.839,2.650,2.582,2.569,2.555,2.538,2.532,2.530,2.548,2.543,2.561,2.546,4.737,4.687,4.814,4.726,4.804,4.530,4.396,2.858},Reflectance=[181]{43.000,43.000,43.000,35.000,43.000,40.000,44.000,42.000,44.000,48.000,46.000,43.000,37.000,43.000,43.000,36.000,49.000,54.000,53.000,47.000,44.000,47.000,50.000,53.000,54.000,49.000,50.000,52.000,48.000,49.000,52.000,53.000,53.000,54.000,55.000,56.000,57.000,57.000,57.000,55.000,54.000,54.000,54.000,52.000,54.000,49.000,52.000,55.000,52.000,48.000,49.000,57.000,55.000,55.000,53.000,55.000,49.000,47.000,44.000,50.000,50.000,54.000,59.000,51.000,56.000,53.000,50.000,59.000,55.000,49.000,52.000,48.000,49.000,47.000,46.000,51.000,50.000,49.000,52.000,66.000,74.000,75.000,75.000,74.000,74.000,71.000,68.000,72.000,71.000,70.000,74.000,75.000,75.000,76.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,76.000,77.000,77.000,109.000,110.000,6.000,112.000,28.000,76.000,126.000,75.000,74.000,76.000,77.000,77.000,78.000,77.000,79.000,69.000,52.000,26.000,83.000,71.000,93.000,85.000,70.000,86.000,65.000,50.000}
-64.734 LMS_LASER_2D_RIGHT LMS2 ID=4132,time=1225719876.374897,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=221,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.643,17.820,15.141,12.454,10.508,9.527,8.715,7.938,7.246,6.678,6.118,5.706,5.398,5.033,4.732,4.465,4.203,4.000,3.813,3.634,3.498,3.336,3.193,3.028,2.886,2.787,2.687,2.587,2.496,2.425,2.353,2.264,2.183,2.145,2.083,2.016,1.941,1.884,1.856,1.784,1.748,1.719,1.680,1.642,1.604,1.569,1.538,1.491,1.454,1.425,1.414,1.387,1.358,1.337,1.303,1.294,1.269,1.250,1.239,1.214,1.191,1.182,1.159,1.141,1.125,1.117,1.100,1.083,1.082,1.085,1.092,1.101,1.108,1.096,1.109,1.114,1.117,1.113,1.106,1.098,1.084,1.072,1.063,1.069,1.038,1.004,1.005,1.016,1.011,0.958,0.951},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,37.000,52.000,110.000,107.000,84.000,61.000,56.000,54.000,57.000,63.000,66.000,66.000,68.000,69.000,70.000,71.000,73.000,74.000,75.000,76.000,78.000,76.000,78.000,80.000,79.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,80.000,80.000,76.000,79.000,80.000,79.000,79.000,78.000,78.000,77.000,76.000,75.000,74.000,74.000,72.000,70.000,65.000,69.000,67.000,69.000,68.000,66.000,67.000,69.000,70.000,73.000,71.000,73.000,73.000,73.000,73.000,71.000,63.000,54.000,47.000,34.000,30.000,33.000,40.000,41.000,45.000,53.000,49.000,50.000,53.000,53.000,44.000,32.000,28.000,29.000,43.000,44.000,26.000,31.000}
-64.743 DESIRED_THRUST iJoystick 86.60237434
-64.743 DESIRED_RUDDER iJoystick 0
-64.747 LMS_LASER_2D_RIGHT LMS2 ID=4133,time=1225719876.388240,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=222,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.392,14.538,12.004,10.302,9.417,8.463,7.801,7.114,6.563,6.017,5.662,5.327,4.963,4.680,4.421,4.169,3.969,3.797,3.613,3.460,3.298,3.156,3.004,2.847,2.740,2.661,2.578,2.487,2.407,2.328,2.220,2.141,2.127,2.059,1.999,1.928,1.884,1.841,1.783,1.749,1.716,1.671,1.624,1.594,1.569,1.526,1.483,1.457,1.429,1.406,1.379,1.355,1.322,1.294,1.292,1.268,1.236,1.217,1.208,1.183,1.158,1.151,1.147,1.130,1.114,1.099,1.087,1.088,1.086,1.091,1.084,1.095,1.105,1.104,1.116,1.115,1.105,1.105,1.090,1.082,1.066,1.058,1.056,1.051,1.002,0.978,1.013,1.001,0.955,0.961},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,78.000,114.000,102.000,78.000,58.000,59.000,54.000,57.000,65.000,66.000,65.000,68.000,70.000,70.000,72.000,74.000,75.000,75.000,77.000,78.000,76.000,78.000,79.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,81.000,78.000,79.000,80.000,79.000,80.000,80.000,80.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,76.000,76.000,76.000,76.000,77.000,77.000,78.000,71.000,68.000,66.000,69.000,72.000,72.000,71.000,72.000,72.000,73.000,66.000,66.000,69.000,71.000,75.000,69.000,65.000,57.000,54.000,42.000,37.000,40.000,42.000,36.000,34.000,40.000,38.000,47.000,54.000,58.000,53.000,41.000,26.000,27.000,40.000,36.000,27.000,33.000}
-64.747 LMS_LASER_2D_LEFT LMS1 ID=4261,time=1225719876.396050,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=2,Range=[181]{1.046,1.063,1.068,1.062,1.082,1.090,1.099,1.100,1.115,1.126,1.132,1.150,1.168,1.181,1.193,1.204,1.212,1.217,1.230,1.245,1.268,1.282,1.295,1.307,1.322,1.346,1.361,1.378,1.401,1.417,1.425,1.453,1.476,1.495,1.529,1.546,1.575,1.604,1.621,1.653,1.680,1.703,1.741,1.779,1.812,1.847,1.867,1.891,1.946,1.988,2.032,2.056,2.130,2.177,2.233,2.281,2.342,2.433,2.482,2.547,2.583,2.570,2.597,2.721,2.771,2.829,2.905,2.951,3.012,3.163,3.272,3.409,3.538,3.645,3.802,3.902,3.909,3.899,3.901,3.893,3.937,3.954,3.951,3.956,3.955,3.963,3.971,3.959,3.986,4.034,4.054,4.050,4.067,4.089,4.092,4.095,4.093,4.100,4.098,4.108,4.104,4.109,4.107,4.110,4.121,4.119,4.129,4.137,4.137,4.145,4.147,4.155,4.164,4.174,4.180,4.189,4.195,4.205,4.215,4.232,4.241,4.251,4.258,4.276,4.283,4.301,4.313,4.329,4.345,4.355,4.367,4.384,4.393,4.409,4.430,4.447,4.456,4.474,4.494,4.520,4.536,4.556,4.573,4.599,4.613,4.641,4.659,4.687,4.713,4.732,4.755,4.776,3.317,3.288,4.870,3.334,3.338,3.177,3.290,3.153,3.121,2.784,2.587,2.563,2.549,2.537,2.534,2.526,2.526,2.521,2.525,2.533,2.548,4.679,4.616,4.741,5.015,5.002,4.487,2.848,2.302},Reflectance=[181]{41.000,41.000,40.000,34.000,42.000,42.000,42.000,47.000,45.000,43.000,46.000,47.000,43.000,41.000,38.000,44.000,44.000,50.000,52.000,48.000,45.000,49.000,46.000,52.000,51.000,53.000,52.000,52.000,54.000,50.000,54.000,54.000,53.000,54.000,53.000,53.000,55.000,56.000,56.000,54.000,54.000,56.000,54.000,51.000,53.000,53.000,54.000,56.000,54.000,46.000,51.000,54.000,49.000,54.000,48.000,56.000,53.000,45.000,49.000,50.000,50.000,56.000,60.000,47.000,53.000,52.000,48.000,64.000,57.000,46.000,52.000,46.000,46.000,46.000,49.000,49.000,48.000,48.000,52.000,68.000,75.000,75.000,75.000,74.000,73.000,71.000,71.000,72.000,70.000,71.000,74.000,76.000,75.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,79.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,76.000,34.000,27.000,76.000,111.000,115.000,27.000,112.000,43.000,32.000,113.000,76.000,77.000,78.000,77.000,79.000,79.000,79.000,77.000,76.000,71.000,58.000,82.000,70.000,91.000,75.000,64.000,94.000,30.000,87.000}
-64.759 LMS_LASER_2D_LEFT LMS1 ID=4262,time=1225719876.409384,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=3,Range=[181]{1.056,1.059,1.063,1.062,1.087,1.086,1.103,1.109,1.119,1.136,1.143,1.157,1.167,1.178,1.189,1.208,1.215,1.230,1.237,1.253,1.277,1.281,1.300,1.317,1.330,1.343,1.355,1.379,1.391,1.409,1.435,1.448,1.474,1.504,1.531,1.555,1.582,1.602,1.624,1.656,1.689,1.717,1.751,1.794,1.814,1.842,1.870,1.902,1.953,2.001,2.035,2.086,2.141,2.186,2.256,2.295,2.352,2.440,2.488,2.546,2.581,2.580,2.611,2.724,2.783,2.850,2.897,2.953,3.002,3.182,3.307,3.446,3.552,3.672,3.820,3.903,3.899,3.903,3.904,3.903,3.933,3.954,3.959,3.954,3.950,3.969,3.963,3.957,3.992,4.037,4.054,4.051,4.066,4.089,4.093,4.094,4.095,4.101,4.100,4.099,4.104,4.110,4.109,4.111,4.120,4.122,4.130,4.130,4.137,4.146,4.157,4.165,4.165,4.173,4.180,4.188,4.193,4.211,4.224,4.241,4.241,4.251,4.260,4.277,4.294,4.304,4.314,4.329,4.339,4.356,4.365,4.382,4.401,4.418,4.428,4.448,4.463,4.474,4.502,4.521,4.537,4.555,4.576,4.600,4.623,4.642,4.661,4.687,4.714,4.738,4.763,3.442,3.394,3.426,3.253,3.326,3.349,3.179,3.274,3.264,3.250,2.708,2.549,2.550,2.541,2.539,2.530,2.522,2.518,2.517,2.514,2.528,2.641,2.560,4.621,4.681,5.011,5.010,4.455,2.276,2.134},Reflectance=[181]{42.000,38.000,35.000,33.000,37.000,44.000,44.000,43.000,43.000,44.000,43.000,45.000,42.000,44.000,41.000,42.000,38.000,36.000,43.000,47.000,45.000,48.000,49.000,49.000,50.000,52.000,53.000,52.000,53.000,54.000,54.000,56.000,56.000,54.000,54.000,53.000,54.000,56.000,58.000,55.000,54.000,54.000,50.000,50.000,54.000,55.000,55.000,54.000,53.000,52.000,49.000,52.000,50.000,50.000,49.000,55.000,46.000,46.000,51.000,53.000,53.000,61.000,58.000,48.000,51.000,50.000,56.000,69.000,63.000,47.000,48.000,45.000,49.000,49.000,53.000,50.000,48.000,50.000,57.000,71.000,74.000,75.000,75.000,73.000,72.000,72.000,71.000,71.000,69.000,72.000,74.000,76.000,75.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,107.000,96.000,108.000,31.000,113.000,117.000,45.000,113.000,113.000,117.000,118.000,78.000,78.000,78.000,77.000,79.000,79.000,79.000,79.000,78.000,77.000,114.000,30.000,74.000,84.000,74.000,79.000,98.000,118.000,77.000}
-64.759 LMS_LASER_2D_RIGHT LMS2 ID=4134,time=1225719876.401582,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=223,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.441,-1.000,16.918,14.061,11.621,10.118,9.239,8.436,7.676,7.000,6.467,5.971,5.612,5.264,4.917,4.629,4.375,4.126,3.940,3.755,3.590,3.420,3.273,3.129,2.988,2.829,2.727,2.653,2.569,2.485,2.397,2.309,2.165,2.124,2.130,2.053,1.976,1.918,1.875,1.830,1.777,1.741,1.716,1.654,1.607,1.580,1.557,1.515,1.463,1.432,1.417,1.389,1.372,1.356,1.323,1.303,1.277,1.252,1.238,1.227,1.208,1.183,1.159,1.151,1.139,1.131,1.120,1.090,1.086,1.082,1.080,1.085,1.083,1.100,1.104,1.093,1.096,1.103,1.094,1.096,1.097,1.082,1.074,1.048,1.045,1.039,1.037,0.990,0.999,0.972,0.953,0.944},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,3.000,0.000,82.000,117.000,100.000,72.000,59.000,55.000,53.000,59.000,65.000,65.000,66.000,68.000,69.000,71.000,71.000,73.000,75.000,76.000,78.000,79.000,78.000,79.000,79.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,77.000,77.000,76.000,76.000,77.000,77.000,77.000,77.000,78.000,76.000,68.000,68.000,72.000,74.000,73.000,70.000,71.000,73.000,73.000,69.000,67.000,64.000,72.000,75.000,72.000,68.000,63.000,57.000,47.000,40.000,32.000,31.000,31.000,31.000,35.000,42.000,50.000,53.000,57.000,56.000,53.000,37.000,26.000,31.000,26.000,25.000,30.000}
-64.767 DESIRED_THRUST iJoystick 86.60237434
-64.767 DESIRED_RUDDER iJoystick 0
-64.770 LMS_LASER_2D_LEFT LMS1 ID=4263,time=1225719876.422716,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=4,Range=[181]{1.054,1.056,1.044,1.065,1.085,1.089,1.095,1.116,1.118,1.134,1.140,1.160,1.168,1.185,1.195,1.205,1.217,1.225,1.244,1.252,1.269,1.283,1.290,1.315,1.328,1.346,1.355,1.382,1.405,1.418,1.435,1.452,1.479,1.504,1.530,1.565,1.590,1.611,1.634,1.663,1.688,1.722,1.758,1.793,1.814,1.843,1.871,1.914,1.961,1.997,2.037,2.087,2.151,2.198,2.259,2.292,2.375,2.450,2.496,2.540,2.582,2.587,2.651,2.736,2.781,2.858,2.901,2.951,2.977,3.201,3.347,3.464,3.564,3.682,3.844,3.910,3.897,3.902,3.888,3.904,3.936,3.954,3.959,3.948,3.956,3.972,3.961,3.960,3.997,4.039,4.055,4.049,4.077,4.088,4.094,4.094,4.094,4.098,4.099,4.102,4.104,4.106,4.110,4.122,4.117,4.131,4.130,4.131,4.137,4.146,4.155,4.162,4.165,4.173,4.179,4.187,4.200,4.212,4.232,4.242,4.252,4.258,4.268,4.285,4.293,4.306,4.322,4.338,4.348,4.356,4.373,4.385,4.402,4.419,4.438,4.449,4.474,4.483,4.503,4.521,4.548,4.565,4.583,4.599,4.625,4.642,4.668,4.688,4.714,4.741,3.462,3.316,3.302,3.394,3.399,3.320,3.281,3.206,3.148,3.136,3.099,2.674,2.550,2.551,2.543,2.535,2.526,2.522,2.522,2.511,2.517,2.516,2.603,2.549,4.640,4.722,4.922,5.024,2.185,2.096,2.096},Reflectance=[181]{35.000,35.000,32.000,32.000,39.000,46.000,44.000,42.000,43.000,47.000,45.000,39.000,39.000,38.000,44.000,44.000,42.000,42.000,42.000,47.000,47.000,49.000,48.000,48.000,53.000,53.000,53.000,53.000,52.000,54.000,54.000,54.000,54.000,54.000,54.000,54.000,53.000,56.000,58.000,55.000,54.000,53.000,53.000,53.000,54.000,56.000,55.000,55.000,53.000,54.000,53.000,52.000,47.000,48.000,51.000,54.000,44.000,46.000,55.000,59.000,53.000,60.000,55.000,50.000,53.000,50.000,58.000,69.000,66.000,47.000,51.000,46.000,45.000,46.000,49.000,49.000,47.000,49.000,57.000,71.000,75.000,75.000,75.000,71.000,71.000,73.000,70.000,72.000,71.000,73.000,75.000,75.000,76.000,76.000,78.000,78.000,78.000,77.000,77.000,78.000,79.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,76.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,109.000,75.000,74.000,104.000,115.000,107.000,105.000,12.000,32.000,54.000,33.000,120.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,97.000,55.000,72.000,75.000,65.000,85.000,45.000,71.000,71.000}
-64.770 LMS_LASER_2D_RIGHT LMS2 ID=4135,time=1225719876.414921,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=224,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.122,-1.000,16.687,13.562,11.388,9.980,9.093,8.279,7.537,6.893,6.408,5.903,5.595,5.219,4.889,4.595,4.313,4.109,3.915,3.730,3.571,3.379,3.246,3.111,2.964,2.818,2.720,2.655,2.561,2.477,2.380,2.300,2.172,2.135,2.103,2.047,1.959,1.918,1.875,1.824,1.776,1.752,1.708,1.653,1.614,1.569,1.542,1.519,1.462,1.433,1.420,1.399,1.372,1.357,1.333,1.288,1.261,1.236,1.236,1.216,1.207,1.189,1.165,1.142,1.140,1.122,1.113,1.089,1.082,1.081,1.072,1.079,1.086,1.094,1.081,1.075,1.093,1.081,1.090,1.096,1.079,1.076,1.062,1.060,1.047,1.039,1.039,0.990,1.006,0.965,0.956,0.932},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,21.000,0.000,92.000,122.000,96.000,69.000,58.000,55.000,56.000,60.000,64.000,66.000,66.000,68.000,69.000,71.000,73.000,74.000,75.000,76.000,78.000,78.000,78.000,79.000,80.000,79.000,80.000,81.000,81.000,80.000,80.000,80.000,80.000,79.000,80.000,81.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,78.000,75.000,78.000,77.000,75.000,77.000,78.000,77.000,77.000,78.000,76.000,71.000,72.000,74.000,73.000,70.000,69.000,67.000,68.000,73.000,70.000,69.000,66.000,70.000,72.000,70.000,69.000,66.000,59.000,48.000,31.000,28.000,30.000,29.000,30.000,40.000,52.000,58.000,56.000,51.000,52.000,53.000,46.000,28.000,34.000,26.000,26.000,29.000}
-64.771 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.6793,20.5412,-0.9323},Vel=[3x1]{-0.7469,-0.5543,2.8205},Raw=[2x1]{23.1695,-0.9323},time=1225719876.41853165626526,Speed=0.93017143190911,Pitch=0.02243353733839,Roll=0.02916359853990,PitchDot=-0.03813701347526,RollDot=0.00060570550814
-64.771 ODOMETRY_POSE iPlatform Pose=[3x1]{6.6793,20.5412,-0.9318},Vel=[3x1]{-0.7469,-0.5543,2.8203},Raw=[2x1]{23.1695,-0.9323},time=1225719876.4185,Speed=0.9302,Pitch=-0.0100,Roll=0.0354,PitchDot=0.0364,RollDot=0.0115
-64.782 LMS_LASER_2D_RIGHT LMS2 ID=4136,time=1225719876.428260,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=225,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.181,-1.000,16.376,13.337,11.181,9.850,9.022,8.180,7.474,6.879,6.357,5.868,5.535,5.173,4.846,4.570,4.283,4.102,3.905,3.708,3.544,3.366,3.223,3.086,2.938,2.818,2.722,2.637,2.543,2.461,2.371,2.291,2.224,2.128,2.064,2.039,1.969,1.918,1.873,1.821,1.777,1.743,1.706,1.651,1.631,1.569,1.542,1.511,1.459,1.432,1.419,1.390,1.361,1.345,1.318,1.304,1.261,1.248,1.227,1.216,1.199,1.190,1.157,1.141,1.133,1.121,1.097,1.089,1.083,1.075,1.073,1.076,1.091,1.100,1.072,1.075,1.078,1.092,1.097,1.098,1.078,1.070,1.063,1.069,1.048,1.047,1.038,1.015,0.975,0.962,0.949,0.938},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,19.000,0.000,96.000,119.000,93.000,68.000,57.000,56.000,56.000,62.000,65.000,66.000,66.000,68.000,69.000,71.000,73.000,74.000,75.000,77.000,78.000,77.000,77.000,79.000,80.000,79.000,80.000,81.000,81.000,81.000,80.000,80.000,79.000,77.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,78.000,78.000,76.000,78.000,77.000,74.000,77.000,78.000,77.000,77.000,77.000,75.000,71.000,72.000,75.000,74.000,70.000,70.000,68.000,69.000,72.000,71.000,67.000,68.000,69.000,73.000,73.000,69.000,62.000,53.000,43.000,29.000,28.000,29.000,31.000,32.000,40.000,60.000,59.000,53.000,42.000,50.000,49.000,49.000,33.000,26.000,27.000,26.000,29.000}
-64.791 DESIRED_THRUST iJoystick 86.60237434
-64.791 DESIRED_RUDDER iJoystick 0
-64.782 LMS_LASER_2D_LEFT LMS1 ID=4264,time=1225719876.436047,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=5,Range=[181]{1.033,1.048,1.053,1.082,1.084,1.096,1.102,1.115,1.129,1.132,1.148,1.163,1.173,1.181,1.189,1.205,1.219,1.238,1.242,1.259,1.275,1.287,1.298,1.326,1.334,1.346,1.357,1.381,1.401,1.423,1.442,1.468,1.486,1.506,1.530,1.565,1.593,1.617,1.638,1.663,1.702,1.723,1.759,1.786,1.822,1.844,1.877,1.913,1.966,1.999,2.040,2.096,2.159,2.207,2.262,2.303,2.384,2.461,2.513,2.534,2.585,2.584,2.674,2.731,2.777,2.861,2.913,2.956,3.014,3.229,3.371,3.469,3.573,3.711,3.857,3.910,3.899,3.901,3.891,3.910,3.934,3.953,3.958,3.947,3.954,3.976,3.962,3.967,4.005,4.038,4.057,4.049,4.078,4.090,4.095,4.095,4.094,4.102,4.101,4.097,4.104,4.108,4.111,4.110,4.117,4.121,4.131,4.131,4.147,4.147,4.154,4.166,4.165,4.173,4.179,4.194,4.200,4.215,4.233,4.243,4.251,4.260,4.278,4.286,4.294,4.314,4.323,4.336,4.349,4.356,4.376,4.393,4.402,4.420,4.429,4.449,4.466,4.485,4.503,4.520,4.539,4.556,4.583,4.599,4.626,4.644,4.670,4.688,4.714,3.347,3.419,3.340,3.366,3.296,3.408,3.313,3.180,4.957,3.142,3.265,3.113,2.582,2.560,2.558,2.551,2.534,2.526,2.522,2.520,2.513,2.511,2.508,2.521,2.631,2.565,4.871,4.891,2.185,2.139,2.091,2.092},Reflectance=[181]{31.000,33.000,33.000,42.000,43.000,40.000,43.000,46.000,44.000,45.000,45.000,40.000,37.000,45.000,46.000,44.000,39.000,40.000,41.000,45.000,49.000,47.000,48.000,49.000,52.000,53.000,54.000,53.000,54.000,53.000,53.000,53.000,54.000,55.000,54.000,54.000,51.000,54.000,55.000,55.000,52.000,54.000,54.000,54.000,54.000,56.000,54.000,55.000,52.000,55.000,54.000,50.000,46.000,48.000,52.000,55.000,43.000,47.000,55.000,66.000,55.000,58.000,53.000,55.000,55.000,51.000,55.000,59.000,58.000,49.000,53.000,53.000,45.000,48.000,55.000,49.000,48.000,49.000,59.000,73.000,75.000,75.000,74.000,71.000,71.000,72.000,71.000,72.000,71.000,72.000,75.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,76.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,77.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,22.000,102.000,79.000,87.000,14.000,115.000,109.000,34.000,76.000,30.000,114.000,25.000,69.000,76.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,77.000,105.000,38.000,76.000,77.000,46.000,73.000,72.000,72.000}
-64.798 LMS_LASER_2D_RIGHT LMS2 ID=4137,time=1225719876.441600,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=226,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.022,23.097,16.150,13.175,11.133,9.839,8.961,8.122,7.390,6.801,6.297,5.839,5.527,5.155,4.817,4.544,4.265,4.075,3.889,3.697,3.511,3.359,3.213,3.077,2.891,2.809,2.716,2.626,2.541,2.469,2.372,2.283,2.219,2.098,2.041,2.024,1.977,1.916,1.864,1.821,1.777,1.750,1.695,1.659,1.621,1.574,1.542,1.510,1.462,1.431,1.408,1.376,1.369,1.352,1.323,1.303,1.268,1.244,1.235,1.216,1.198,1.174,1.165,1.149,1.132,1.114,1.105,1.089,1.077,1.075,1.073,1.077,1.087,1.097,1.086,1.072,1.090,1.111,1.105,1.099,1.071,1.067,1.060,1.066,1.049,1.052,1.035,1.027,0.974,0.963,0.965,0.938},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,27.000,6.000,105.000,120.000,91.000,67.000,57.000,57.000,57.000,62.000,65.000,66.000,66.000,68.000,69.000,71.000,73.000,74.000,75.000,76.000,77.000,78.000,77.000,79.000,81.000,79.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,81.000,82.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,75.000,78.000,78.000,77.000,78.000,77.000,75.000,74.000,75.000,75.000,76.000,77.000,72.000,69.000,69.000,74.000,72.000,71.000,68.000,70.000,69.000,71.000,69.000,69.000,69.000,69.000,74.000,73.000,69.000,63.000,56.000,40.000,31.000,29.000,29.000,37.000,45.000,47.000,56.000,58.000,55.000,38.000,34.000,42.000,48.000,40.000,28.000,26.000,29.000,29.000}
-64.799 LMS_LASER_2D_LEFT LMS1 ID=4265,time=1225719876.449381,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=6,Range=[181]{1.035,1.045,1.063,1.066,1.076,1.083,1.096,1.110,1.122,1.129,1.146,1.153,1.161,1.167,1.189,1.197,1.210,1.219,1.240,1.259,1.278,1.283,1.301,1.316,1.338,1.353,1.370,1.389,1.401,1.417,1.445,1.476,1.493,1.521,1.546,1.572,1.606,1.632,1.643,1.673,1.702,1.737,1.763,1.795,1.818,1.829,1.876,1.917,1.959,1.995,2.050,2.102,2.161,2.203,2.275,2.312,2.376,2.463,2.506,2.535,2.585,2.586,2.682,2.733,2.768,2.849,2.906,2.987,3.116,3.243,3.385,3.489,3.578,3.724,3.845,3.904,3.902,3.897,3.886,3.910,3.936,3.951,3.959,3.947,3.953,3.976,3.952,3.966,4.001,4.042,4.057,4.049,4.077,4.091,4.093,4.094,4.094,4.099,4.101,4.102,4.099,4.111,4.111,4.122,4.120,4.121,4.130,4.131,4.137,4.149,4.154,4.164,4.164,4.174,4.181,4.186,4.195,4.217,4.234,4.243,4.252,4.260,4.276,4.285,4.306,4.314,4.321,4.339,4.348,4.356,4.374,4.384,4.400,4.419,4.438,4.448,4.466,4.485,4.503,4.520,4.538,4.565,4.582,4.599,4.625,4.643,4.669,4.686,4.725,4.738,3.519,3.438,3.355,3.229,3.207,3.292,3.177,4.966,3.119,3.153,3.084,2.625,2.591,2.571,2.557,2.549,2.532,2.523,2.517,2.513,2.504,2.508,2.508,2.517,2.486,2.143,2.175,2.192,2.175,2.206,2.154},Reflectance=[181]{32.000,33.000,43.000,43.000,41.000,43.000,46.000,45.000,45.000,44.000,45.000,42.000,42.000,43.000,46.000,42.000,40.000,41.000,46.000,46.000,47.000,49.000,49.000,48.000,50.000,52.000,52.000,52.000,54.000,54.000,51.000,53.000,53.000,54.000,53.000,50.000,45.000,53.000,54.000,55.000,52.000,45.000,52.000,54.000,56.000,64.000,54.000,56.000,56.000,56.000,55.000,52.000,47.000,43.000,54.000,55.000,44.000,48.000,56.000,66.000,55.000,59.000,53.000,60.000,60.000,53.000,56.000,54.000,49.000,47.000,52.000,53.000,45.000,46.000,57.000,50.000,49.000,47.000,61.000,73.000,75.000,75.000,75.000,71.000,70.000,72.000,70.000,72.000,69.000,74.000,75.000,75.000,76.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,79.000,77.000,113.000,104.000,9.000,37.000,33.000,106.000,29.000,76.000,26.000,5.000,24.000,59.000,74.000,77.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,76.000,58.000,29.000,49.000,78.000,82.000,93.000,55.000}
-64.807 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.7021,20.5582,-0.9316},Vel=[3x1]{-0.7430,-0.5522,1.5385},Raw=[2x1]{23.1979,-0.9316},time=1225719876.45457577705383,Speed=0.92579071872901,Pitch=0.02019018360455,Roll=0.03140695227374,PitchDot=-0.04711042841061,RollDot=0.00085247441886
-64.807 ODOMETRY_POSE iPlatform Pose=[3x1]{6.7021,20.5582,-0.9311},Vel=[3x1]{-0.7430,-0.5522,1.5385},Raw=[2x1]{23.1979,-0.9316},time=1225719876.4546,Speed=0.9258,Pitch=-0.0132,Roll=0.0349,PitchDot=-0.0007,RollDot=0.0471
-64.810 LMS_LASER_2D_RIGHT LMS2 ID=4138,time=1225719876.454940,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=227,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.098,-1.000,16.072,13.113,11.040,9.777,8.950,8.120,7.377,6.793,6.297,5.812,5.518,5.137,4.807,4.535,4.265,4.074,3.898,3.690,3.511,3.355,3.213,3.042,2.916,2.802,2.696,2.614,2.533,2.460,2.362,2.283,2.186,2.064,2.032,2.023,1.969,1.918,1.866,1.811,1.768,1.739,1.698,1.660,1.610,1.578,1.541,1.509,1.466,1.433,1.405,1.379,1.360,1.335,1.324,1.295,1.269,1.243,1.225,1.207,1.190,1.173,1.157,1.150,1.132,1.114,1.106,1.088,1.082,1.069,1.074,1.071,1.083,1.088,1.103,1.084,1.092,1.105,1.098,1.086,1.084,1.065,1.061,1.064,1.059,1.039,1.039,1.028,1.011,0.962,0.959,0.932},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,24.000,0.000,107.000,117.000,90.000,66.000,56.000,56.000,55.000,62.000,65.000,66.000,66.000,68.000,69.000,72.000,73.000,74.000,75.000,77.000,77.000,76.000,77.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,81.000,81.000,82.000,81.000,80.000,80.000,80.000,79.000,80.000,79.000,74.000,78.000,77.000,78.000,78.000,73.000,72.000,74.000,73.000,73.000,74.000,77.000,74.000,70.000,69.000,72.000,70.000,69.000,67.000,68.000,70.000,71.000,70.000,68.000,69.000,69.000,71.000,75.000,72.000,67.000,58.000,52.000,39.000,30.000,31.000,40.000,57.000,59.000,58.000,57.000,59.000,49.000,41.000,32.000,40.000,44.000,39.000,27.000,28.000,29.000}
-64.815 DESIRED_THRUST iJoystick 86.60237434
-64.815 DESIRED_RUDDER iJoystick 0
-64.810 LMS_LASER_2D_LEFT LMS1 ID=4266,time=1225719876.462713,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=7,Range=[181]{1.042,1.048,1.052,1.070,1.072,1.089,1.099,1.104,1.116,1.138,1.139,1.153,1.160,1.183,1.188,1.202,1.212,1.224,1.235,1.246,1.271,1.282,1.303,1.318,1.331,1.348,1.376,1.391,1.407,1.424,1.448,1.479,1.486,1.520,1.547,1.568,1.601,1.627,1.640,1.662,1.707,1.742,1.760,1.801,1.821,1.825,1.865,1.934,1.962,2.001,2.056,2.103,2.156,2.223,2.269,2.304,2.384,2.462,2.519,2.548,2.576,2.585,2.690,2.718,2.759,2.858,2.916,2.984,3.125,3.242,3.390,3.490,3.583,3.727,3.846,3.904,3.899,3.897,3.887,3.912,3.942,3.951,3.958,3.944,3.947,3.969,3.950,3.964,4.001,4.039,4.058,4.045,4.077,4.091,4.087,4.087,4.095,4.100,4.100,4.101,4.101,4.104,4.104,4.114,4.121,4.122,4.131,4.138,4.137,4.148,4.147,4.164,4.164,4.174,4.180,4.188,4.203,4.206,4.225,4.243,4.252,4.252,4.260,4.278,4.295,4.314,4.321,4.330,4.348,4.356,4.374,4.393,4.403,4.420,4.429,4.448,4.466,4.485,4.504,4.522,4.540,4.553,4.583,4.600,4.626,4.652,4.670,4.688,4.714,4.740,4.772,4.785,3.235,3.301,4.881,3.180,4.937,4.957,3.091,5.016,3.074,2.671,2.625,2.592,2.585,2.574,2.560,2.530,2.522,2.511,2.505,2.472,2.337,2.308,2.208,2.131,2.143,2.229,2.068,2.097,2.152},Reflectance=[181]{37.000,43.000,41.000,44.000,43.000,39.000,45.000,44.000,45.000,46.000,43.000,41.000,44.000,47.000,44.000,41.000,41.000,43.000,39.000,48.000,52.000,49.000,50.000,53.000,51.000,50.000,51.000,53.000,53.000,53.000,52.000,51.000,54.000,53.000,54.000,43.000,32.000,51.000,56.000,54.000,50.000,46.000,54.000,52.000,58.000,70.000,56.000,53.000,54.000,56.000,54.000,52.000,41.000,47.000,55.000,55.000,48.000,48.000,54.000,58.000,55.000,59.000,49.000,62.000,56.000,50.000,56.000,57.000,46.000,47.000,50.000,50.000,46.000,47.000,57.000,50.000,48.000,47.000,62.000,73.000,74.000,75.000,74.000,70.000,69.000,70.000,69.000,71.000,69.000,73.000,75.000,75.000,76.000,77.000,78.000,79.000,78.000,77.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,76.000,21.000,88.000,77.000,32.000,76.000,76.000,30.000,75.000,19.000,20.000,56.000,69.000,75.000,77.000,78.000,77.000,78.000,79.000,80.000,80.000,84.000,84.000,78.000,71.000,74.000,92.000,68.000,62.000,55.000}
-64.823 LMS_LASER_2D_RIGHT LMS2 ID=4139,time=1225719876.468279,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=228,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.152,-1.000,16.089,13.114,11.054,9.777,8.977,8.137,7.424,6.824,6.297,5.821,5.510,5.129,4.827,4.560,4.265,4.073,3.905,3.680,3.512,3.358,3.218,3.050,2.892,2.795,2.697,2.613,2.534,2.460,2.364,2.292,2.171,2.053,2.030,2.019,1.969,1.927,1.863,1.819,1.770,1.738,1.691,1.649,1.608,1.578,1.550,1.505,1.456,1.430,1.414,1.379,1.371,1.352,1.324,1.288,1.261,1.246,1.235,1.206,1.188,1.171,1.164,1.149,1.131,1.122,1.114,1.103,1.089,1.074,1.073,1.078,1.083,1.081,1.102,1.100,1.103,1.103,1.086,1.077,1.077,1.073,1.059,1.064,1.056,1.051,1.023,1.021,1.012,1.008,0.962,0.924},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,24.000,0.000,107.000,119.000,89.000,67.000,57.000,56.000,57.000,61.000,65.000,66.000,66.000,69.000,68.000,70.000,73.000,74.000,75.000,76.000,77.000,77.000,78.000,79.000,81.000,80.000,80.000,80.000,81.000,80.000,81.000,80.000,82.000,80.000,81.000,80.000,80.000,80.000,79.000,78.000,80.000,78.000,74.000,78.000,77.000,78.000,75.000,67.000,72.000,72.000,73.000,73.000,74.000,77.000,77.000,71.000,72.000,74.000,71.000,67.000,65.000,65.000,66.000,70.000,69.000,69.000,69.000,65.000,69.000,72.000,70.000,65.000,57.000,57.000,43.000,41.000,37.000,48.000,59.000,63.000,59.000,57.000,58.000,53.000,50.000,44.000,53.000,48.000,45.000,43.000,27.000,26.000}
-64.834 LMS_LASER_2D_RIGHT LMS2 ID=4140,time=1225719876.481616,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=229,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.100,23.145,16.250,13.255,11.118,9.832,9.021,8.189,7.466,6.842,6.323,5.850,5.518,5.155,4.836,4.571,4.274,4.085,3.904,3.698,3.533,3.369,3.219,3.053,2.908,2.805,2.697,2.598,2.552,2.461,2.372,2.291,2.188,2.054,2.038,2.025,1.976,1.942,1.870,1.810,1.776,1.732,1.703,1.660,1.616,1.575,1.543,1.498,1.448,1.424,1.407,1.393,1.371,1.355,1.321,1.289,1.273,1.253,1.226,1.207,1.188,1.180,1.164,1.147,1.138,1.131,1.129,1.112,1.081,1.081,1.072,1.070,1.076,1.086,1.099,1.109,1.107,1.094,1.084,1.090,1.074,1.076,1.057,1.054,1.047,1.042,1.028,1.016,1.016,1.009,0.957,0.930},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,26.000,6.000,101.000,119.000,92.000,68.000,57.000,56.000,56.000,61.000,64.000,66.000,66.000,68.000,68.000,71.000,72.000,75.000,74.000,76.000,77.000,78.000,78.000,80.000,81.000,80.000,80.000,81.000,81.000,81.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,70.000,69.000,72.000,74.000,74.000,75.000,74.000,78.000,75.000,73.000,74.000,74.000,72.000,68.000,65.000,66.000,66.000,67.000,67.000,68.000,65.000,64.000,71.000,70.000,69.000,65.000,58.000,51.000,38.000,41.000,46.000,55.000,62.000,61.000,61.000,58.000,61.000,56.000,52.000,50.000,52.000,50.000,50.000,51.000,28.000,27.000}
-64.834 LMS_LASER_2D_LEFT LMS1 ID=4267,time=1225719876.476055,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=8,Range=[181]{1.042,1.050,1.059,1.066,1.071,1.088,1.099,1.110,1.124,1.133,1.147,1.146,1.164,1.181,1.184,1.198,1.205,1.219,1.236,1.246,1.264,1.287,1.304,1.315,1.322,1.352,1.366,1.389,1.406,1.426,1.442,1.475,1.499,1.520,1.553,1.572,1.594,1.640,1.643,1.670,1.710,1.739,1.770,1.795,1.827,1.820,1.846,1.934,1.964,1.998,2.048,2.113,2.157,2.213,2.252,2.305,2.382,2.453,2.515,2.560,2.579,2.581,2.677,2.718,2.750,2.855,2.910,2.984,3.105,3.232,3.371,3.490,3.587,3.716,3.830,3.879,3.901,3.896,3.887,3.909,3.934,3.958,3.954,3.948,3.949,3.968,3.953,3.958,4.001,4.032,4.051,4.049,4.079,4.083,4.086,4.086,4.096,4.102,4.104,4.104,4.104,4.105,4.111,4.113,4.113,4.122,4.122,4.131,4.138,4.139,4.147,4.164,4.165,4.174,4.174,4.189,4.195,4.207,4.226,4.234,4.251,4.257,4.255,4.269,4.295,4.314,4.320,4.331,4.348,4.358,4.375,4.385,4.395,4.412,4.430,4.448,4.469,4.486,4.499,4.522,4.542,4.557,4.584,4.601,4.626,4.643,4.670,4.688,4.712,4.742,4.766,4.784,3.205,3.404,4.874,3.151,4.932,3.094,3.073,5.013,3.076,5.080,5.107,2.716,2.878,2.737,2.657,2.578,2.583,2.524,2.509,2.436,2.269,2.195,2.159,2.136,2.135,2.100,2.089,2.100,2.162},Reflectance=[181]{41.000,41.000,40.000,43.000,42.000,42.000,45.000,48.000,50.000,47.000,45.000,44.000,43.000,46.000,43.000,43.000,42.000,40.000,43.000,41.000,44.000,47.000,47.000,52.000,55.000,52.000,50.000,49.000,52.000,54.000,53.000,45.000,41.000,53.000,49.000,44.000,34.000,52.000,54.000,54.000,47.000,49.000,55.000,54.000,56.000,71.000,62.000,53.000,55.000,54.000,54.000,49.000,46.000,51.000,55.000,56.000,47.000,51.000,55.000,55.000,56.000,57.000,47.000,62.000,55.000,48.000,54.000,57.000,49.000,50.000,50.000,50.000,48.000,46.000,58.000,58.000,49.000,50.000,61.000,72.000,75.000,74.000,73.000,71.000,69.000,70.000,68.000,69.000,69.000,73.000,76.000,75.000,76.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,80.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,76.000,33.000,105.000,77.000,25.000,77.000,21.000,29.000,75.000,14.000,74.000,74.000,17.000,133.000,83.000,83.000,78.000,87.000,78.000,79.000,81.000,83.000,75.000,74.000,75.000,74.000,72.000,66.000,67.000,48.000}
-64.839 DESIRED_THRUST iJoystick 86.60237434
-64.839 DESIRED_RUDDER iJoystick 0
-64.843 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.7320,20.5804,-0.9328},Vel=[3x1]{-0.7448,-0.5523,4.7436},Raw=[2x1]{23.2352,-0.9328},time=1225719876.49049162864685,Speed=0.92725095645571,Pitch=0.01794682987071,Roll=0.03365030600758,PitchDot=-0.03365030600758,RollDot=0.00004486707468
-64.843 ODOMETRY_POSE iPlatform Pose=[3x1]{6.7320,20.5804,-0.9322},Vel=[3x1]{-0.7448,-0.5523,-1.5396},Raw=[2x1]{23.2352,-0.9328},time=1225719876.4905,Speed=0.9273,Pitch=-0.0163,Roll=0.0345,PitchDot=-0.0011,RollDot=-0.0336
-64.844 DB_TIME MOOSDB#1 1225719876.49
-64.844 DB_UPTIME MOOSDB#1 68.3478446007
-64.846 LMS_LASER_2D_RIGHT LMS2 ID=4141,time=1225719876.494951,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=230,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.187,23.181,16.510,13.420,11.287,9.937,9.065,8.229,7.492,6.857,6.374,5.894,5.567,5.201,4.862,4.595,4.283,4.101,3.917,3.706,3.541,3.375,3.230,3.072,2.925,2.823,2.706,2.615,2.543,2.462,2.389,2.300,2.235,2.072,2.048,2.050,1.976,1.942,1.880,1.803,1.767,1.740,1.698,1.659,1.619,1.577,1.537,1.499,1.452,1.436,1.414,1.387,1.371,1.350,1.306,1.281,1.273,1.256,1.234,1.208,1.190,1.174,1.173,1.155,1.145,1.129,1.129,1.104,1.081,1.074,1.072,1.082,1.087,1.094,1.067,1.082,1.096,1.101,1.097,1.082,1.069,1.077,1.062,1.056,1.048,1.036,1.028,1.028,1.015,1.008,0.994,0.941},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,7.000,95.000,122.000,94.000,69.000,58.000,56.000,56.000,60.000,65.000,66.000,65.000,68.000,69.000,71.000,74.000,74.000,75.000,76.000,77.000,77.000,79.000,80.000,81.000,81.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,81.000,81.000,79.000,80.000,80.000,79.000,77.000,79.000,79.000,79.000,78.000,77.000,78.000,74.000,70.000,75.000,75.000,77.000,76.000,77.000,76.000,74.000,74.000,74.000,75.000,71.000,71.000,68.000,70.000,68.000,67.000,64.000,66.000,64.000,66.000,70.000,72.000,67.000,61.000,52.000,44.000,29.000,30.000,31.000,47.000,56.000,61.000,63.000,55.000,56.000,57.000,53.000,55.000,52.000,44.000,53.000,51.000,35.000,26.000}
-64.846 LMS_LASER_2D_LEFT LMS1 ID=4268,time=1225719876.489397,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=9,Range=[181]{1.049,1.044,1.070,1.066,1.072,1.092,1.093,1.105,1.123,1.132,1.144,1.155,1.159,1.177,1.186,1.206,1.200,1.223,1.245,1.252,1.259,1.287,1.300,1.318,1.319,1.346,1.366,1.388,1.402,1.426,1.450,1.467,1.496,1.530,1.547,1.580,1.603,1.625,1.644,1.663,1.706,1.731,1.768,1.797,1.824,1.825,1.837,1.933,1.979,2.000,2.057,2.103,2.160,2.212,2.262,2.311,2.388,2.455,2.507,2.551,2.587,2.585,2.639,2.741,2.803,2.856,2.906,2.982,3.094,3.223,3.352,3.492,3.571,3.697,3.814,3.884,3.894,3.895,3.879,3.909,3.934,3.953,3.957,3.953,3.948,3.964,3.959,3.958,3.993,4.035,4.053,4.051,4.070,4.086,4.085,4.095,4.101,4.096,4.095,4.099,4.108,4.107,4.110,4.119,4.119,4.125,4.127,4.131,4.143,4.147,4.148,4.164,4.167,4.166,4.175,4.188,4.198,4.208,4.226,4.234,4.246,4.244,4.258,4.266,4.286,4.307,4.322,4.332,4.342,4.359,4.370,4.386,4.397,4.412,4.430,4.463,4.472,4.490,4.495,4.526,4.545,4.561,4.576,4.592,4.618,4.644,4.664,4.691,4.716,4.742,4.764,3.203,3.214,3.231,4.864,3.129,4.925,3.100,4.983,5.012,5.047,5.074,5.108,5.138,4.678,2.896,2.782,2.861,2.699,2.573,2.516,2.508,2.492,2.275,2.219,2.160,2.152,2.160,2.136,2.148,2.279},Reflectance=[181]{39.000,42.000,45.000,39.000,43.000,43.000,44.000,42.000,46.000,46.000,45.000,45.000,43.000,48.000,45.000,46.000,43.000,42.000,48.000,43.000,43.000,51.000,52.000,53.000,57.000,53.000,54.000,52.000,51.000,54.000,50.000,37.000,34.000,46.000,50.000,49.000,48.000,54.000,54.000,55.000,50.000,53.000,50.000,55.000,59.000,73.000,66.000,49.000,46.000,55.000,51.000,49.000,47.000,43.000,45.000,43.000,46.000,52.000,56.000,55.000,56.000,55.000,54.000,48.000,48.000,49.000,48.000,52.000,48.000,50.000,53.000,47.000,49.000,46.000,55.000,55.000,49.000,49.000,63.000,72.000,75.000,75.000,74.000,73.000,71.000,71.000,70.000,69.000,70.000,74.000,77.000,76.000,76.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,79.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,78.000,80.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,77.000,79.000,80.000,80.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,80.000,79.000,79.000,79.000,80.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,25.000,35.000,34.000,77.000,24.000,77.000,21.000,76.000,74.000,74.000,74.000,74.000,75.000,81.000,108.000,79.000,109.000,118.000,83.000,78.000,78.000,79.000,83.000,79.000,74.000,75.000,74.000,67.000,76.000,97.000}
-64.859 LMS_LASER_2D_RIGHT LMS2 ID=4142,time=1225719876.508287,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=231,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.310,-1.000,16.710,13.697,11.454,10.022,9.161,8.332,7.590,6.927,6.417,5.927,5.585,5.219,4.880,4.613,4.339,4.119,3.949,3.721,3.566,3.417,3.239,3.097,2.937,2.831,2.712,2.582,2.552,2.470,2.400,2.306,2.247,2.158,2.096,2.041,1.977,1.932,1.862,1.794,1.760,1.743,1.707,1.662,1.623,1.587,1.542,1.497,1.455,1.436,1.414,1.392,1.374,1.351,1.297,1.280,1.266,1.258,1.236,1.234,1.183,1.176,1.175,1.165,1.153,1.136,1.127,1.105,1.089,1.074,1.071,1.074,1.089,1.093,1.086,1.088,1.078,1.104,1.111,1.091,1.082,1.072,1.073,1.058,1.038,1.034,1.021,1.019,1.007,1.011,0.998,0.945},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,0.000,91.000,119.000,97.000,70.000,58.000,56.000,55.000,59.000,64.000,65.000,65.000,68.000,69.000,71.000,72.000,74.000,75.000,76.000,77.000,78.000,79.000,80.000,81.000,81.000,80.000,81.000,81.000,81.000,81.000,79.000,80.000,78.000,80.000,79.000,80.000,79.000,79.000,79.000,80.000,80.000,79.000,79.000,78.000,78.000,78.000,75.000,76.000,75.000,76.000,78.000,78.000,76.000,73.000,73.000,75.000,75.000,73.000,69.000,72.000,74.000,71.000,68.000,63.000,63.000,62.000,67.000,70.000,72.000,67.000,61.000,52.000,43.000,35.000,32.000,29.000,37.000,44.000,53.000,57.000,52.000,53.000,54.000,53.000,58.000,52.000,51.000,57.000,52.000,41.000,25.000}
-64.863 DESIRED_THRUST iJoystick 86.60237434
-64.863 DESIRED_RUDDER iJoystick 0
-64.879 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.7542,20.5968,-0.9347},Vel=[3x1]{-0.7412,-0.5474,7.3077},Raw=[2x1]{23.2628,-0.9347},time=1225719876.52659463882446,Speed=0.92141000554890,Pitch=0.01794682987071,Roll=0.03365030600758,PitchDot=-0.03813701347526,RollDot=-0.00058327197080
-64.879 ODOMETRY_POSE iPlatform Pose=[3x1]{6.7542,20.5968,-0.9341},Vel=[3x1]{-0.7412,-0.5474,1.0249},Raw=[2x1]{23.2628,-0.9347},time=1225719876.5266,Speed=0.9214,Pitch=-0.0164,Roll=0.0344,PitchDot=-0.0203,RollDot=0.0323
-64.859 LMS_LASER_2D_LEFT LMS1 ID=4269,time=1225719876.502737,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=10,Range=[181]{1.038,1.049,1.058,1.063,1.077,1.078,1.098,1.108,1.113,1.119,1.134,1.154,1.162,1.170,1.188,1.194,1.213,1.234,1.237,1.245,1.278,1.281,1.296,1.311,1.316,1.327,1.370,1.384,1.407,1.425,1.443,1.452,1.483,1.519,1.551,1.571,1.593,1.618,1.638,1.663,1.689,1.724,1.761,1.788,1.818,1.822,1.846,1.915,1.969,2.004,2.052,2.100,2.155,2.209,2.252,2.314,2.374,2.443,2.496,2.558,2.593,2.578,2.627,2.734,2.777,2.845,2.903,2.998,3.090,3.218,3.341,3.467,3.555,3.672,3.778,3.886,3.903,3.893,3.875,3.898,3.925,3.950,3.950,3.949,3.946,3.966,3.962,3.950,3.997,4.036,4.054,4.051,4.064,4.085,4.087,4.087,4.099,4.096,4.097,4.099,4.100,4.103,4.107,4.110,4.119,4.118,4.127,4.127,4.132,4.148,4.149,4.157,4.158,4.167,4.176,4.184,4.191,4.204,4.208,4.226,4.237,4.250,4.259,4.266,4.281,4.307,4.314,4.328,4.344,4.352,4.363,4.381,4.395,4.413,4.433,4.453,4.472,4.479,4.501,4.515,4.531,4.549,4.568,4.595,4.610,4.638,4.655,4.681,4.706,4.737,4.759,3.206,3.268,4.830,4.855,3.156,4.915,4.949,4.974,3.070,5.044,5.064,5.097,5.135,5.168,2.952,2.869,2.849,2.925,2.733,2.437,2.330,2.340,2.435,2.331,2.271,2.267,2.291,2.184,2.180,2.152},Reflectance=[181]{43.000,36.000,41.000,43.000,44.000,42.000,46.000,47.000,44.000,41.000,43.000,49.000,49.000,41.000,42.000,41.000,42.000,47.000,44.000,44.000,47.000,48.000,51.000,53.000,60.000,57.000,52.000,54.000,53.000,54.000,46.000,28.000,30.000,44.000,48.000,49.000,51.000,55.000,56.000,55.000,54.000,54.000,51.000,55.000,56.000,69.000,63.000,55.000,50.000,53.000,49.000,47.000,49.000,45.000,40.000,44.000,51.000,55.000,55.000,55.000,54.000,56.000,57.000,49.000,48.000,48.000,47.000,52.000,50.000,48.000,48.000,48.000,50.000,50.000,51.000,53.000,49.000,52.000,59.000,72.000,74.000,74.000,74.000,74.000,71.000,72.000,71.000,69.000,68.000,75.000,77.000,76.000,77.000,78.000,78.000,78.000,79.000,78.000,79.000,77.000,77.000,78.000,79.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,80.000,80.000,80.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,24.000,27.000,77.000,77.000,10.000,77.000,77.000,76.000,16.000,76.000,74.000,74.000,72.000,67.000,112.000,101.000,98.000,112.000,89.000,103.000,85.000,85.000,81.000,83.000,84.000,81.000,63.000,74.000,75.000,75.000}
-64.870 LMS_LASER_2D_RIGHT LMS2 ID=4143,time=1225719876.521621,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=232,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,27.604,17.146,14.088,11.621,10.153,9.240,8.453,7.670,6.999,6.466,5.963,5.611,5.263,4.925,4.638,4.366,4.136,3.959,3.759,3.584,3.427,3.251,3.131,2.947,2.842,2.734,2.617,2.572,2.497,2.410,2.318,2.240,2.176,2.104,2.044,1.983,1.944,1.843,1.777,1.770,1.743,1.707,1.661,1.623,1.587,1.558,1.507,1.475,1.449,1.418,1.398,1.374,1.354,1.297,1.280,1.266,1.264,1.244,1.233,1.199,1.175,1.174,1.166,1.154,1.137,1.119,1.097,1.082,1.067,1.073,1.069,1.081,1.081,1.087,1.086,1.066,1.069,1.084,1.098,1.094,1.082,1.073,1.067,1.041,1.035,1.027,1.013,1.007,1.010,1.004,0.949},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,5.000,101.000,116.000,100.000,73.000,59.000,54.000,54.000,58.000,63.000,66.000,66.000,67.000,68.000,70.000,72.000,74.000,75.000,74.000,76.000,79.000,78.000,80.000,82.000,81.000,78.000,81.000,81.000,81.000,81.000,80.000,81.000,78.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,75.000,70.000,72.000,73.000,75.000,77.000,78.000,77.000,74.000,74.000,75.000,74.000,74.000,68.000,70.000,71.000,70.000,70.000,66.000,66.000,63.000,69.000,71.000,74.000,69.000,63.000,53.000,53.000,39.000,32.000,28.000,28.000,30.000,36.000,39.000,47.000,50.000,50.000,54.000,58.000,59.000,60.000,58.000,51.000,42.000,26.000}
-64.871 LMS_LASER_2D_LEFT LMS1 ID=4270,time=1225719876.516076,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=11,Range=[181]{1.037,1.053,1.057,1.067,1.073,1.084,1.086,1.095,1.122,1.117,1.135,1.148,1.166,1.171,1.186,1.196,1.215,1.225,1.234,1.253,1.270,1.283,1.302,1.312,1.305,1.317,1.356,1.377,1.401,1.421,1.438,1.448,1.493,1.517,1.537,1.564,1.593,1.606,1.632,1.662,1.688,1.716,1.755,1.786,1.824,1.840,1.892,1.932,1.971,1.998,2.048,2.091,2.150,2.199,2.253,2.310,2.360,2.432,2.481,2.552,2.588,2.579,2.598,2.713,2.780,2.830,2.880,2.968,3.085,3.183,3.314,3.446,3.539,3.655,3.725,3.861,3.895,3.885,3.879,3.898,3.925,3.943,3.951,3.948,3.947,3.956,3.955,3.948,3.989,4.026,4.054,4.051,4.063,4.076,4.087,4.087,4.096,4.096,4.093,4.102,4.108,4.111,4.114,4.101,4.110,4.111,4.119,4.127,4.134,4.139,4.149,4.149,4.157,4.167,4.178,4.186,4.191,4.202,4.209,4.209,4.231,4.243,4.253,4.265,4.270,4.294,4.314,4.314,4.338,4.348,4.364,4.379,4.388,4.404,4.422,4.451,4.466,4.479,4.500,4.513,4.531,4.553,4.561,4.595,4.611,4.629,4.652,4.672,4.699,4.725,4.751,4.773,4.793,4.824,3.127,3.125,4.912,4.941,4.968,5.010,5.035,5.066,5.090,5.125,5.099,4.504,2.918,2.788,2.832,2.755,2.315,2.224,2.224,2.289,2.358,2.490,2.330,2.322,2.230,2.225,2.183},Reflectance=[181]{42.000,38.000,43.000,44.000,45.000,41.000,42.000,42.000,46.000,43.000,44.000,46.000,45.000,45.000,45.000,42.000,38.000,45.000,47.000,47.000,47.000,49.000,49.000,54.000,59.000,60.000,54.000,51.000,54.000,52.000,41.000,30.000,38.000,52.000,50.000,53.000,55.000,58.000,57.000,54.000,54.000,54.000,52.000,54.000,55.000,54.000,46.000,45.000,46.000,51.000,54.000,51.000,46.000,49.000,48.000,51.000,46.000,54.000,56.000,56.000,52.000,56.000,56.000,47.000,50.000,49.000,48.000,50.000,48.000,51.000,48.000,46.000,47.000,47.000,50.000,50.000,49.000,52.000,61.000,72.000,74.000,75.000,75.000,74.000,73.000,71.000,71.000,71.000,71.000,74.000,77.000,76.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,80.000,81.000,79.000,78.000,78.000,79.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,78.000,78.000,76.000,77.000,17.000,18.000,78.000,77.000,77.000,76.000,76.000,75.000,74.000,74.000,74.000,80.000,124.000,80.000,85.000,81.000,92.000,75.000,78.000,85.000,85.000,80.000,83.000,82.000,77.000,76.000,76.000}
-64.883 LMS_LASER_2D_LEFT LMS1 ID=4271,time=1225719876.529415,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=12,Range=[181]{1.042,1.041,1.055,1.068,1.071,1.075,1.087,1.104,1.111,1.120,1.134,1.147,1.148,1.163,1.181,1.195,1.209,1.219,1.237,1.248,1.266,1.278,1.290,1.308,1.310,1.301,1.331,1.379,1.401,1.416,1.433,1.444,1.489,1.513,1.534,1.562,1.589,1.605,1.625,1.663,1.690,1.718,1.741,1.789,1.806,1.856,1.896,1.927,1.970,1.998,2.042,2.081,2.144,2.194,2.256,2.291,2.354,2.429,2.480,2.543,2.583,2.574,2.590,2.707,2.772,2.814,2.874,2.950,3.094,3.195,3.293,3.416,3.513,3.650,3.738,3.864,3.892,3.882,3.871,3.885,3.925,3.945,3.954,3.956,3.954,3.962,3.958,3.952,3.982,4.024,4.051,4.047,4.058,4.077,4.085,4.097,4.099,4.096,4.097,4.094,4.098,4.096,4.109,4.101,4.111,4.122,4.119,4.129,4.136,4.136,4.146,4.149,4.163,4.167,4.175,4.184,4.191,4.197,4.206,4.218,4.231,4.239,4.252,4.259,4.279,4.295,4.298,4.317,4.335,4.347,4.355,4.374,4.392,4.410,4.422,4.442,4.458,4.485,4.500,4.512,4.546,4.554,4.563,4.590,4.603,4.620,4.649,4.672,4.699,4.725,4.743,4.771,4.800,4.823,3.104,4.883,4.913,4.937,4.968,5.003,5.030,5.057,5.094,4.461,4.378,5.195,2.839,2.869,2.794,2.790,2.463,2.279,2.226,2.224,2.287,2.326,2.499,2.294,2.188,2.178,2.166},Reflectance=[181]{44.000,43.000,43.000,45.000,42.000,40.000,42.000,44.000,44.000,42.000,43.000,45.000,43.000,42.000,43.000,44.000,43.000,44.000,48.000,49.000,49.000,51.000,52.000,52.000,62.000,66.000,55.000,52.000,54.000,53.000,42.000,30.000,31.000,54.000,52.000,52.000,53.000,57.000,58.000,55.000,55.000,55.000,54.000,51.000,55.000,52.000,47.000,50.000,46.000,51.000,55.000,54.000,51.000,46.000,49.000,57.000,51.000,56.000,56.000,56.000,54.000,58.000,57.000,49.000,46.000,49.000,53.000,53.000,48.000,49.000,50.000,49.000,48.000,49.000,48.000,47.000,48.000,51.000,64.000,70.000,74.000,75.000,75.000,76.000,75.000,73.000,72.000,72.000,71.000,73.000,76.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,77.000,79.000,81.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,80.000,79.000,79.000,79.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,80.000,80.000,79.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,77.000,22.000,77.000,78.000,78.000,77.000,77.000,77.000,75.000,75.000,95.000,93.000,77.000,56.000,108.000,80.000,81.000,91.000,83.000,76.000,75.000,85.000,86.000,82.000,85.000,77.000,77.000,76.000}
-64.887 DESIRED_THRUST iJoystick 86.60237434
-64.887 DESIRED_RUDDER iJoystick 0
-64.064 CAMERA_FILE_WRITE iCameraLadybug time=1225719875.712,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.712-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.712-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.712-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.712-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719875.712-4.jpg
-64.883 LMS_LASER_2D_RIGHT LMS2 ID=4144,time=1225719876.534954,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=233,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,27.661,17.369,14.357,11.895,10.258,9.356,8.542,7.783,7.090,6.512,6.024,5.646,5.299,4.945,4.663,4.394,4.146,3.977,3.785,3.601,3.440,3.274,3.130,2.971,2.867,2.750,2.631,2.572,2.505,2.415,2.327,2.249,2.183,2.115,2.054,1.999,1.950,1.829,1.788,1.788,1.752,1.707,1.670,1.624,1.597,1.560,1.512,1.479,1.449,1.427,1.393,1.374,1.360,1.306,1.280,1.268,1.264,1.248,1.233,1.213,1.190,1.181,1.164,1.150,1.129,1.114,1.097,1.081,1.081,1.064,1.062,1.074,1.080,1.088,1.080,1.084,1.067,1.064,1.070,1.060,1.080,1.077,1.064,1.041,1.035,1.025,1.009,1.006,1.010,1.002,0.949},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,9.000,96.000,116.000,102.000,76.000,60.000,54.000,54.000,58.000,63.000,65.000,66.000,67.000,69.000,69.000,71.000,75.000,75.000,75.000,76.000,77.000,79.000,79.000,82.000,81.000,78.000,82.000,81.000,80.000,80.000,80.000,81.000,80.000,81.000,80.000,79.000,79.000,81.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,75.000,63.000,67.000,73.000,75.000,75.000,78.000,77.000,73.000,74.000,75.000,77.000,75.000,68.000,66.000,69.000,69.000,67.000,61.000,64.000,67.000,67.000,69.000,70.000,70.000,66.000,58.000,49.000,45.000,34.000,32.000,29.000,27.000,29.000,27.000,34.000,41.000,49.000,54.000,58.000,62.000,63.000,57.000,51.000,48.000,26.000}
-64.894 LMS_LASER_2D_LEFT LMS1 ID=4272,time=1225719876.542751,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=13,Range=[181]{1.036,1.043,1.058,1.057,1.069,1.074,1.093,1.104,1.104,1.132,1.131,1.144,1.161,1.171,1.178,1.190,1.211,1.219,1.233,1.244,1.267,1.277,1.285,1.305,1.321,1.310,1.330,1.367,1.397,1.419,1.438,1.443,1.471,1.510,1.524,1.558,1.593,1.610,1.620,1.653,1.682,1.718,1.750,1.778,1.802,1.825,1.871,1.925,1.958,1.992,2.036,2.073,2.123,2.189,2.242,2.280,2.332,2.427,2.467,2.542,2.573,2.563,2.586,2.706,2.759,2.806,2.861,2.946,3.063,3.182,3.272,3.371,3.507,3.628,3.742,3.837,3.889,3.881,3.862,3.880,3.911,3.939,3.946,3.942,3.942,3.955,3.960,3.943,3.969,4.012,4.040,4.044,4.047,4.091,4.097,4.101,4.097,4.096,4.099,4.096,4.099,4.099,4.102,4.109,4.109,4.111,4.120,4.122,4.128,4.138,4.147,4.147,4.155,4.167,4.173,4.175,4.184,4.191,4.199,4.214,4.232,4.234,4.252,4.253,4.269,4.278,4.298,4.320,4.328,4.348,4.356,4.370,4.390,4.401,4.409,4.431,4.454,4.476,4.491,4.504,4.536,4.551,4.569,4.588,4.595,4.621,4.638,4.664,4.691,4.719,4.742,4.766,4.793,4.825,4.842,4.875,4.905,4.927,4.961,4.993,5.020,5.052,5.078,4.373,4.271,4.369,5.229,2.930,2.909,2.799,2.788,2.282,2.228,2.233,2.226,2.253,2.334,2.254,2.161,2.159,2.147},Reflectance=[181]{42.000,44.000,47.000,39.000,41.000,39.000,40.000,44.000,42.000,46.000,43.000,48.000,45.000,45.000,44.000,39.000,48.000,48.000,50.000,47.000,50.000,50.000,50.000,51.000,54.000,62.000,58.000,55.000,52.000,55.000,48.000,30.000,27.000,44.000,48.000,39.000,47.000,55.000,59.000,58.000,55.000,55.000,54.000,54.000,62.000,59.000,52.000,49.000,48.000,52.000,56.000,58.000,49.000,48.000,47.000,60.000,52.000,55.000,54.000,55.000,57.000,57.000,59.000,48.000,48.000,50.000,47.000,51.000,50.000,47.000,52.000,50.000,45.000,47.000,46.000,46.000,50.000,51.000,65.000,71.000,73.000,76.000,75.000,74.000,74.000,73.000,72.000,72.000,72.000,72.000,76.000,77.000,77.000,77.000,77.000,78.000,79.000,79.000,79.000,80.000,79.000,79.000,80.000,81.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,80.000,80.000,78.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,80.000,80.000,79.000,81.000,80.000,80.000,79.000,80.000,80.000,80.000,79.000,80.000,79.000,81.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,79.000,78.000,77.000,77.000,77.000,75.000,75.000,91.000,86.000,100.000,76.000,130.000,123.000,72.000,69.000,66.000,69.000,75.000,78.000,84.000,86.000,85.000,75.000,77.000,75.000}
-64.906 LMS_LASER_2D_RIGHT LMS2 ID=4145,time=1225719876.548295,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=234,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.819,17.724,14.876,12.240,10.490,9.449,8.624,7.856,7.156,6.597,6.098,5.697,5.363,4.990,4.706,4.429,4.163,4.007,3.812,3.607,3.442,3.299,3.135,3.013,2.883,2.783,2.647,2.590,2.506,2.415,2.345,2.272,2.209,2.140,2.071,2.010,1.953,1.858,1.813,1.797,1.759,1.715,1.679,1.635,1.598,1.564,1.520,1.479,1.453,1.431,1.400,1.381,1.361,1.315,1.289,1.266,1.257,1.247,1.234,1.224,1.198,1.189,1.187,1.158,1.145,1.114,1.099,1.097,1.087,1.079,1.071,1.069,1.076,1.086,1.084,1.098,1.095,1.086,1.055,1.064,1.076,1.076,1.071,1.045,1.044,1.030,1.010,1.011,1.011,1.012,0.994},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,14.000,89.000,112.000,107.000,81.000,61.000,56.000,54.000,56.000,63.000,66.000,66.000,68.000,70.000,70.000,72.000,75.000,76.000,75.000,78.000,78.000,78.000,78.000,81.000,81.000,79.000,82.000,81.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,79.000,77.000,62.000,60.000,66.000,72.000,75.000,77.000,77.000,73.000,73.000,75.000,78.000,75.000,69.000,68.000,68.000,67.000,63.000,61.000,63.000,68.000,72.000,68.000,67.000,66.000,67.000,64.000,58.000,51.000,47.000,40.000,32.000,31.000,27.000,29.000,33.000,44.000,45.000,52.000,51.000,56.000,59.000,56.000,52.000,45.000,39.000}
-64.906 LMS_LASER_2D_LEFT LMS1 ID=4273,time=1225719876.556085,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=14,Range=[181]{1.036,1.043,1.046,1.063,1.070,1.083,1.089,1.099,1.112,1.121,1.126,1.143,1.152,1.168,1.174,1.194,1.202,1.219,1.231,1.243,1.256,1.270,1.290,1.302,1.325,1.329,1.347,1.369,1.390,1.409,1.430,1.454,1.453,1.505,1.530,1.557,1.585,1.593,1.617,1.644,1.682,1.716,1.742,1.774,1.789,1.811,1.846,1.907,1.953,1.987,2.032,2.055,2.080,2.170,2.228,2.255,2.306,2.420,2.443,2.517,2.554,2.567,2.578,2.690,2.751,2.804,2.868,2.947,3.055,3.179,3.263,3.379,3.498,3.620,3.734,3.810,3.864,3.884,3.877,3.872,3.906,3.930,3.946,3.942,3.942,3.948,3.961,3.942,3.959,3.995,4.031,4.042,4.041,4.086,4.088,4.094,4.089,4.093,4.096,4.090,4.096,4.094,4.106,4.096,4.097,4.107,4.116,4.114,4.123,4.122,4.134,4.146,4.150,4.158,4.170,4.174,4.183,4.187,4.195,4.207,4.215,4.235,4.243,4.255,4.266,4.278,4.286,4.305,4.323,4.335,4.352,4.361,4.382,4.388,4.403,4.422,4.447,4.466,4.492,4.503,4.521,4.548,4.551,4.572,4.595,4.611,4.630,4.653,4.678,4.704,4.732,4.754,4.778,4.813,4.830,4.866,4.896,4.925,4.951,4.975,5.012,4.520,4.506,4.702,4.134,4.267,4.432,4.346,4.344,4.343,4.152,5.158,2.251,2.280,2.321,2.290,2.322,2.198,2.164,2.190,2.180},Reflectance=[181]{42.000,41.000,43.000,38.000,42.000,40.000,43.000,47.000,45.000,44.000,44.000,44.000,44.000,47.000,45.000,45.000,48.000,48.000,46.000,47.000,49.000,51.000,52.000,49.000,52.000,54.000,54.000,52.000,53.000,47.000,44.000,34.000,28.000,34.000,39.000,38.000,43.000,55.000,58.000,54.000,55.000,50.000,54.000,52.000,59.000,63.000,61.000,52.000,50.000,46.000,51.000,65.000,62.000,43.000,46.000,66.000,56.000,52.000,55.000,61.000,61.000,55.000,59.000,49.000,49.000,49.000,46.000,48.000,50.000,49.000,49.000,53.000,44.000,47.000,46.000,49.000,54.000,52.000,52.000,69.000,72.000,73.000,75.000,74.000,74.000,74.000,72.000,72.000,72.000,70.000,73.000,76.000,76.000,76.000,76.000,78.000,77.000,78.000,79.000,77.000,78.000,78.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,80.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,78.000,79.000,80.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,79.000,77.000,77.000,77.000,77.000,92.000,95.000,89.000,74.000,91.000,102.000,96.000,101.000,100.000,22.000,76.000,22.000,71.000,83.000,84.000,83.000,80.000,75.000,78.000,77.000}
-64.911 DESIRED_THRUST iJoystick 85.5708487197
-64.911 DESIRED_RUDDER iJoystick 0
-64.915 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.7844,20.6190,-0.9375},Vel=[3x1]{-0.7557,-0.5548,7.3077},Raw=[2x1]{23.3003,-0.9375},time=1225719876.56251168251038,Speed=0.93747262054262,Pitch=0.01570347613687,Roll=0.03365030600758,PitchDot=-0.03365030600758,RollDot=-0.00067300612015
-64.915 ODOMETRY_POSE iPlatform Pose=[3x1]{6.7844,20.6190,-0.9369},Vel=[3x1]{-0.7557,-0.5548,1.0248},Raw=[2x1]{23.3003,-0.9375},time=1225719876.5625,Speed=0.9375,Pitch=-0.0178,Roll=0.0326,PitchDot=-0.0181,RollDot=0.0284
-64.919 LMS_LASER_2D_RIGHT LMS2 ID=4146,time=1225719876.561637,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=235,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.698,18.053,15.437,12.614,10.738,9.585,8.761,7.975,7.250,6.669,6.172,5.749,5.414,5.033,4.757,4.474,4.179,4.032,3.838,3.641,3.465,3.306,3.158,3.051,2.906,2.818,2.688,2.595,2.514,2.407,2.353,2.288,2.227,2.156,2.087,2.020,1.969,1.918,1.859,1.813,1.768,1.721,1.679,1.637,1.607,1.564,1.525,1.488,1.471,1.429,1.404,1.384,1.368,1.341,1.306,1.280,1.263,1.257,1.236,1.217,1.206,1.189,1.173,1.154,1.136,1.115,1.100,1.090,1.086,1.078,1.072,1.071,1.069,1.088,1.094,1.094,1.095,1.095,1.060,1.070,1.058,1.071,1.072,1.056,1.043,1.027,1.025,1.022,1.013,1.003,0.972},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,28.000,70.000,107.000,112.000,85.000,64.000,56.000,55.000,55.000,63.000,66.000,66.000,67.000,70.000,70.000,71.000,74.000,75.000,75.000,75.000,77.000,78.000,76.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,75.000,80.000,80.000,78.000,79.000,77.000,79.000,77.000,70.000,66.000,66.000,70.000,71.000,75.000,76.000,76.000,73.000,72.000,77.000,75.000,72.000,72.000,67.000,66.000,68.000,65.000,64.000,69.000,74.000,72.000,66.000,65.000,69.000,66.000,63.000,52.000,48.000,48.000,33.000,32.000,27.000,29.000,28.000,34.000,40.000,50.000,51.000,55.000,54.000,49.000,49.000,37.000,30.000}
-64.919 LMS_LASER_2D_LEFT LMS1 ID=4274,time=1225719876.569419,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=15,Range=[181]{1.026,1.041,1.046,1.059,1.070,1.074,1.090,1.098,1.100,1.110,1.124,1.139,1.151,1.163,1.175,1.181,1.192,1.217,1.230,1.243,1.254,1.273,1.281,1.294,1.321,1.332,1.348,1.365,1.389,1.405,1.423,1.439,1.460,1.503,1.524,1.558,1.575,1.586,1.615,1.646,1.672,1.711,1.726,1.767,1.785,1.809,1.837,1.895,1.948,1.988,2.024,2.055,2.063,2.168,2.229,2.250,2.266,2.400,2.446,2.505,2.537,2.554,2.569,2.653,2.744,2.806,2.860,2.920,3.021,3.159,3.248,3.369,3.492,3.592,3.720,3.803,3.863,3.886,3.880,3.871,3.900,3.932,3.937,3.934,3.933,3.938,3.959,3.938,3.949,3.981,4.029,4.041,4.031,4.077,4.090,4.093,4.092,4.093,4.087,4.090,4.096,4.095,4.087,4.099,4.099,4.105,4.105,4.113,4.118,4.122,4.123,4.134,4.140,4.149,4.159,4.167,4.175,4.187,4.194,4.208,4.217,4.224,4.234,4.241,4.259,4.269,4.285,4.295,4.311,4.323,4.341,4.358,4.381,4.384,4.403,4.420,4.437,4.458,4.483,4.494,4.513,4.544,4.549,4.564,4.583,4.608,4.629,4.644,4.670,4.704,4.733,4.746,4.776,4.813,4.833,4.857,4.883,4.918,4.943,4.969,5.005,4.348,4.255,4.305,4.068,4.102,4.284,4.222,4.257,4.284,4.336,4.395,2.270,2.282,2.319,2.303,2.310,2.247,2.156,2.245,2.562},Reflectance=[181]{42.000,41.000,43.000,40.000,42.000,43.000,45.000,46.000,40.000,44.000,54.000,49.000,40.000,44.000,47.000,43.000,43.000,45.000,45.000,47.000,48.000,49.000,52.000,50.000,50.000,51.000,54.000,50.000,49.000,49.000,42.000,31.000,28.000,33.000,34.000,47.000,47.000,55.000,57.000,55.000,55.000,52.000,55.000,53.000,57.000,60.000,63.000,55.000,48.000,46.000,51.000,61.000,65.000,46.000,46.000,67.000,67.000,55.000,56.000,59.000,69.000,57.000,59.000,52.000,46.000,57.000,54.000,47.000,50.000,49.000,49.000,52.000,47.000,46.000,45.000,50.000,57.000,53.000,54.000,64.000,72.000,74.000,75.000,75.000,74.000,73.000,75.000,71.000,72.000,69.000,72.000,76.000,75.000,76.000,77.000,78.000,77.000,78.000,78.000,77.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,79.000,80.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,97.000,93.000,97.000,68.000,73.000,95.000,90.000,95.000,96.000,102.000,100.000,23.000,63.000,83.000,83.000,83.000,84.000,76.000,82.000,100.000}
-64.930 LMS_LASER_2D_RIGHT LMS2 ID=4147,time=1225719876.574976,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=236,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.818,23.196,15.773,12.881,10.879,9.750,8.906,8.091,7.386,6.740,6.270,5.831,5.484,5.068,4.817,4.518,4.216,4.045,3.878,3.674,3.501,3.339,3.191,3.080,2.929,2.848,2.740,2.620,2.514,2.411,2.349,2.304,2.224,2.161,2.104,2.037,1.975,1.912,1.878,1.818,1.759,1.725,1.684,1.634,1.616,1.584,1.536,1.507,1.481,1.447,1.412,1.395,1.379,1.348,1.306,1.279,1.268,1.261,1.239,1.217,1.199,1.182,1.166,1.156,1.130,1.114,1.099,1.091,1.081,1.080,1.073,1.069,1.077,1.089,1.092,1.104,1.100,1.087,1.060,1.060,1.047,1.043,1.071,1.070,1.050,1.034,1.021,1.024,1.023,1.004,1.001},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,25.000,2.000,104.000,114.000,88.000,66.000,56.000,55.000,55.000,62.000,64.000,66.000,67.000,70.000,69.000,71.000,75.000,74.000,74.000,74.000,77.000,77.000,75.000,80.000,79.000,80.000,80.000,79.000,80.000,79.000,79.000,78.000,79.000,79.000,80.000,80.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,79.000,78.000,76.000,76.000,75.000,71.000,69.000,72.000,77.000,75.000,73.000,72.000,76.000,76.000,75.000,72.000,69.000,70.000,70.000,68.000,66.000,69.000,72.000,74.000,70.000,67.000,70.000,64.000,59.000,52.000,43.000,39.000,34.000,30.000,27.000,27.000,27.000,27.000,35.000,44.000,47.000,54.000,56.000,50.000,46.000,40.000,41.000}
-64.935 DESIRED_THRUST iJoystick 85.5708487197
-64.935 DESIRED_RUDDER iJoystick 0
-64.942 LMS_LASER_2D_RIGHT LMS2 ID=4148,time=1225719876.588314,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=237,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.840,-1.000,16.158,13.227,11.129,9.884,9.004,8.185,7.465,6.834,6.348,5.885,5.543,5.164,4.855,4.552,4.293,4.091,3.887,3.716,3.539,3.345,3.203,3.089,2.954,2.850,2.750,2.626,2.532,2.459,2.377,2.323,2.235,2.158,2.103,2.051,1.985,1.920,1.869,1.816,1.761,1.730,1.705,1.653,1.620,1.588,1.558,1.517,1.485,1.450,1.421,1.389,1.373,1.344,1.313,1.271,1.279,1.261,1.236,1.213,1.200,1.191,1.166,1.140,1.121,1.114,1.106,1.091,1.082,1.081,1.080,1.071,1.080,1.089,1.096,1.100,1.100,1.096,1.086,1.055,1.045,1.048,1.063,1.071,1.058,1.031,1.030,1.029,1.010,1.011,0.989},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,24.000,0.000,97.000,117.000,90.000,67.000,57.000,54.000,56.000,61.000,64.000,66.000,66.000,69.000,70.000,71.000,72.000,74.000,74.000,74.000,76.000,76.000,76.000,80.000,79.000,81.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,78.000,80.000,80.000,80.000,78.000,78.000,78.000,75.000,76.000,78.000,77.000,78.000,79.000,78.000,76.000,77.000,74.000,71.000,74.000,75.000,74.000,71.000,74.000,72.000,72.000,74.000,75.000,72.000,70.000,70.000,69.000,67.000,69.000,69.000,73.000,72.000,69.000,68.000,66.000,60.000,53.000,48.000,47.000,38.000,35.000,31.000,27.000,27.000,27.000,32.000,42.000,41.000,53.000,53.000,45.000,37.000,39.000,34.000}
-64.951 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.8146,20.6412,-0.9395},Vel=[3x1]{-0.7533,-0.5507,0.7692},Raw=[2x1]{23.3377,-0.9395},time=1225719876.59856557846069,Speed=0.93309190736252,Pitch=0.01570347613687,Roll=0.02916359853990,PitchDot=-0.01570347613687,RollDot=-0.00091977503087
-64.951 ODOMETRY_POSE iPlatform Pose=[3x1]{6.8146,20.6412,-0.9391},Vel=[3x1]{-0.7533,-0.5507,0.7693},Raw=[2x1]{23.3377,-0.9395},time=1225719876.5986,Speed=0.9331,Pitch=-0.0143,Roll=0.0299,PitchDot=-0.0119,RollDot=0.0103
-64.955 LMS_LASER_2D_RIGHT LMS2 ID=4149,time=1225719876.601652,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=238,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.913,-1.000,16.522,13.472,11.327,10.022,9.118,8.297,7.562,6.916,6.399,5.945,5.603,5.219,4.890,4.579,4.331,4.117,3.915,3.730,3.557,3.363,3.212,3.110,2.960,2.861,2.749,2.642,2.547,2.476,2.389,2.327,2.255,2.189,2.113,2.051,2.002,1.944,1.859,1.815,1.779,1.737,1.708,1.658,1.603,1.586,1.561,1.531,1.490,1.466,1.422,1.396,1.381,1.357,1.332,1.286,1.300,1.268,1.241,1.210,1.200,1.183,1.148,1.139,1.123,1.106,1.107,1.089,1.090,1.082,1.073,1.073,1.069,1.078,1.084,1.088,1.107,1.093,1.087,1.087,1.060,1.043,1.072,1.069,1.048,1.040,1.048,1.031,1.024,1.008,0.993},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,16.000,0.000,93.000,120.000,93.000,70.000,58.000,56.000,55.000,62.000,63.000,66.000,65.000,68.000,70.000,72.000,72.000,73.000,75.000,75.000,77.000,76.000,76.000,78.000,78.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,78.000,77.000,77.000,75.000,80.000,75.000,67.000,75.000,78.000,78.000,78.000,76.000,72.000,73.000,74.000,76.000,72.000,69.000,64.000,68.000,67.000,72.000,71.000,71.000,68.000,68.000,70.000,71.000,71.000,71.000,72.000,72.000,71.000,69.000,63.000,59.000,54.000,52.000,46.000,32.000,30.000,30.000,27.000,27.000,40.000,44.000,53.000,57.000,46.000,36.000,41.000,51.000,35.000}
-64.959 DESIRED_THRUST iJoystick 85.5708487197
-64.959 DESIRED_RUDDER iJoystick 0
-64.942 LMS_LASER_2D_LEFT LMS1 ID=4275,time=1225719876.582762,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=16,Range=[181]{1.037,1.038,1.053,1.049,1.067,1.079,1.085,1.093,1.106,1.094,1.122,1.137,1.138,1.156,1.177,1.183,1.190,1.212,1.228,1.235,1.256,1.266,1.276,1.291,1.311,1.324,1.343,1.364,1.385,1.405,1.422,1.450,1.459,1.481,1.520,1.536,1.571,1.581,1.607,1.632,1.662,1.707,1.718,1.761,1.777,1.793,1.842,1.886,1.949,1.976,2.016,2.051,2.100,2.158,2.221,2.246,2.253,2.381,2.423,2.496,2.527,2.554,2.567,2.634,2.737,2.788,2.830,2.918,3.006,3.155,3.237,3.347,3.477,3.591,3.696,3.814,3.853,3.878,3.872,3.871,3.889,3.922,3.934,3.937,3.937,3.940,3.956,3.944,3.942,3.975,4.013,4.041,4.031,4.067,4.093,4.096,4.096,4.084,4.084,4.086,4.092,4.087,4.087,4.096,4.096,4.102,4.103,4.104,4.111,4.122,4.121,4.131,4.141,4.145,4.150,4.166,4.170,4.180,4.189,4.199,4.217,4.225,4.232,4.241,4.249,4.269,4.277,4.295,4.313,4.324,4.341,4.350,4.367,4.385,4.403,4.411,4.428,4.454,4.476,4.495,4.513,4.530,4.539,4.556,4.583,4.600,4.621,4.643,4.669,4.696,4.722,4.748,4.768,4.794,4.824,4.849,4.883,4.908,4.935,4.967,4.998,4.373,4.192,4.205,4.085,4.087,4.187,4.141,4.273,4.314,4.333,4.369,2.265,2.234,2.237,2.261,2.349,2.277,2.212,2.261,2.514},Reflectance=[181]{46.000,43.000,45.000,40.000,41.000,46.000,44.000,44.000,38.000,29.000,43.000,49.000,42.000,43.000,48.000,45.000,43.000,48.000,48.000,43.000,49.000,50.000,54.000,49.000,50.000,52.000,52.000,50.000,47.000,49.000,42.000,37.000,29.000,28.000,35.000,42.000,53.000,58.000,54.000,57.000,54.000,54.000,55.000,55.000,58.000,62.000,55.000,54.000,48.000,49.000,51.000,55.000,55.000,50.000,46.000,62.000,68.000,54.000,58.000,55.000,66.000,63.000,59.000,55.000,46.000,56.000,60.000,46.000,48.000,47.000,44.000,54.000,48.000,50.000,49.000,51.000,57.000,57.000,54.000,62.000,71.000,73.000,75.000,75.000,75.000,74.000,74.000,72.000,72.000,67.000,70.000,76.000,75.000,75.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,79.000,79.000,79.000,79.000,80.000,78.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,76.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,96.000,89.000,90.000,73.000,71.000,83.000,74.000,90.000,97.000,99.000,100.000,50.000,73.000,74.000,80.000,82.000,83.000,82.000,83.000,78.000}
-64.955 LMS_LASER_2D_LEFT LMS1 ID=4276,time=1225719876.596105,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=17,Range=[181]{1.039,1.033,1.047,1.046,1.062,1.080,1.087,1.098,1.103,1.109,1.120,1.137,1.147,1.165,1.175,1.185,1.197,1.205,1.214,1.229,1.250,1.262,1.282,1.290,1.310,1.327,1.345,1.364,1.382,1.392,1.416,1.433,1.459,1.475,1.506,1.534,1.563,1.588,1.617,1.635,1.668,1.699,1.730,1.755,1.766,1.775,1.822,1.863,1.907,1.970,2.009,2.051,2.099,2.154,2.208,2.236,2.264,2.378,2.428,2.505,2.535,2.557,2.563,2.619,2.738,2.780,2.823,2.906,2.995,3.138,3.237,3.330,3.448,3.580,3.670,3.797,3.854,3.878,3.872,3.862,3.884,3.916,3.928,3.937,3.936,3.940,3.958,3.946,3.942,3.979,4.015,4.032,4.031,4.055,4.085,4.083,4.085,4.087,4.075,4.077,4.084,4.076,4.092,4.087,4.101,4.102,4.107,4.104,4.114,4.123,4.123,4.127,4.138,4.140,4.152,4.159,4.168,4.176,4.188,4.195,4.207,4.217,4.232,4.241,4.257,4.267,4.276,4.285,4.309,4.314,4.338,4.352,4.359,4.375,4.394,4.412,4.428,4.446,4.469,4.485,4.503,4.530,4.539,4.557,4.574,4.593,4.618,4.636,4.659,4.695,4.719,4.736,4.771,4.788,4.811,4.846,4.872,4.900,4.925,4.961,4.988,5.012,4.177,4.122,4.172,4.127,4.131,4.095,4.385,5.292,4.427,2.269,2.231,2.272,2.312,2.296,2.229,2.446,2.271,2.324,2.495},Reflectance=[181]{46.000,44.000,38.000,43.000,44.000,46.000,45.000,46.000,41.000,40.000,42.000,49.000,42.000,46.000,47.000,48.000,44.000,44.000,44.000,44.000,46.000,48.000,49.000,48.000,49.000,49.000,49.000,50.000,45.000,43.000,42.000,37.000,32.000,28.000,30.000,40.000,42.000,49.000,54.000,54.000,53.000,54.000,53.000,56.000,64.000,64.000,58.000,52.000,52.000,53.000,48.000,48.000,51.000,48.000,49.000,63.000,62.000,53.000,56.000,55.000,63.000,58.000,61.000,58.000,47.000,53.000,57.000,48.000,47.000,51.000,49.000,55.000,52.000,53.000,52.000,55.000,61.000,57.000,54.000,61.000,72.000,75.000,75.000,75.000,75.000,74.000,74.000,73.000,72.000,68.000,71.000,76.000,75.000,75.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,79.000,80.000,79.000,79.000,79.000,79.000,79.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,80.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,77.000,90.000,79.000,83.000,79.000,80.000,71.000,92.000,74.000,98.000,29.000,67.000,82.000,95.000,91.000,81.000,80.000,85.000,84.000,77.000}
-64.966 LMS_LASER_2D_RIGHT LMS2 ID=4150,time=1225719876.614987,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=239,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.011,-1.000,16.737,13.739,11.522,10.057,9.135,8.315,7.607,6.993,6.407,5.971,5.603,5.245,4.908,4.588,4.330,4.117,3.925,3.740,3.569,3.382,3.210,3.111,2.960,2.853,2.747,2.653,2.547,2.462,2.390,2.319,2.255,2.190,2.121,2.061,2.010,1.944,1.870,1.817,1.794,1.758,1.707,1.633,1.594,1.579,1.560,1.522,1.496,1.466,1.431,1.405,1.378,1.360,1.339,1.303,1.303,1.269,1.250,1.217,1.201,1.192,1.174,1.149,1.133,1.124,1.114,1.113,1.097,1.081,1.073,1.064,1.080,1.082,1.079,1.088,1.089,1.092,1.096,1.095,1.090,1.058,1.080,1.058,1.052,1.035,1.036,1.030,1.005,1.015,1.004},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,15.000,0.000,89.000,119.000,96.000,72.000,58.000,56.000,55.000,60.000,64.000,65.000,66.000,67.000,69.000,71.000,72.000,73.000,75.000,76.000,77.000,77.000,76.000,79.000,78.000,80.000,80.000,80.000,79.000,78.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,78.000,79.000,79.000,79.000,70.000,66.000,71.000,75.000,78.000,78.000,77.000,74.000,74.000,71.000,73.000,69.000,68.000,68.000,70.000,69.000,72.000,74.000,72.000,70.000,71.000,72.000,72.000,69.000,66.000,68.000,70.000,69.000,69.000,60.000,57.000,56.000,52.000,32.000,33.000,37.000,32.000,34.000,29.000,45.000,57.000,59.000,55.000,52.000,49.000,53.000,50.000,45.000}
-64.966 LMS_LASER_2D_LEFT LMS1 ID=4277,time=1225719876.609446,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=18,Range=[181]{1.025,1.047,1.050,1.059,1.071,1.079,1.079,1.084,1.099,1.100,1.119,1.126,1.136,1.166,1.161,1.170,1.188,1.211,1.220,1.233,1.244,1.261,1.279,1.292,1.311,1.327,1.338,1.364,1.381,1.404,1.416,1.418,1.442,1.471,1.494,1.542,1.568,1.593,1.618,1.632,1.662,1.689,1.717,1.755,1.757,1.773,1.802,1.852,1.872,1.967,2.008,2.049,2.097,2.153,2.201,2.231,2.263,2.359,2.430,2.496,2.532,2.551,2.554,2.600,2.727,2.772,2.822,2.899,2.986,3.135,3.223,3.317,3.430,3.569,3.635,3.791,3.837,3.877,3.873,3.859,3.882,3.913,3.929,3.932,3.934,3.930,3.946,3.944,3.936,3.963,4.005,4.028,4.025,4.044,4.084,4.087,4.085,4.085,4.083,4.075,4.081,4.077,4.087,4.086,4.087,4.096,4.095,4.104,4.114,4.113,4.121,4.125,4.134,4.140,4.150,4.163,4.170,4.180,4.183,4.196,4.205,4.215,4.224,4.240,4.248,4.259,4.276,4.284,4.304,4.317,4.332,4.349,4.358,4.377,4.394,4.404,4.420,4.448,4.466,4.484,4.501,4.520,4.539,4.547,4.576,4.592,4.617,4.636,4.659,4.687,4.702,4.738,4.753,4.777,4.812,4.839,4.866,4.898,4.925,4.961,4.988,5.013,4.161,4.093,4.216,4.156,4.141,4.143,4.363,4.579,5.324,2.274,2.321,2.377,2.244,2.321,2.286,2.474,2.463,2.346,2.489},Reflectance=[181]{40.000,46.000,40.000,45.000,45.000,45.000,42.000,37.000,43.000,43.000,42.000,44.000,42.000,46.000,41.000,42.000,42.000,45.000,48.000,50.000,47.000,47.000,43.000,45.000,50.000,49.000,50.000,50.000,45.000,37.000,33.000,30.000,27.000,27.000,29.000,40.000,48.000,51.000,55.000,57.000,54.000,54.000,54.000,52.000,64.000,68.000,66.000,55.000,52.000,49.000,51.000,51.000,50.000,48.000,45.000,59.000,61.000,53.000,53.000,47.000,60.000,60.000,63.000,57.000,50.000,50.000,56.000,49.000,47.000,50.000,50.000,56.000,56.000,52.000,57.000,59.000,64.000,52.000,55.000,59.000,72.000,74.000,75.000,76.000,75.000,73.000,73.000,72.000,72.000,68.000,71.000,75.000,76.000,74.000,78.000,79.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,90.000,78.000,91.000,83.000,80.000,74.000,94.000,94.000,70.000,39.000,91.000,124.000,40.000,96.000,82.000,80.000,80.000,83.000,78.000}
-64.983 DESIRED_THRUST iJoystick 85.5708487197
-64.983 DESIRED_RUDDER iJoystick 0
-64.987 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.8375,20.6579,-0.9399},Vel=[3x1]{-0.7641,-0.5582,-2.9487},Raw=[2x1]{23.3660,-0.9399},time=1225719876.63452076911926,Speed=0.94623404690284,Pitch=0.01570347613687,Roll=0.02692024480606,PitchDot=-0.00000000000000,RollDot=-0.00017946829871
-64.987 ODOMETRY_POSE iPlatform Pose=[3x1]{6.8375,20.6579,-0.9395},Vel=[3x1]{-0.7641,-0.5582,-2.9487},Raw=[2x1]{23.3660,-0.9399},time=1225719876.6345,Speed=0.9462,Pitch=-0.0125,Roll=0.0286,PitchDot=0.0000,RollDot=0.0002
-64.987 VEHICLE_GEOMETRY iPlatform Name=LISA, Sensor_0=LMS_LASER_2D, Pose3D_0=[4x1]{0.0000,0.3500,0.0000,0.0000},SHAPE_2D=[2x8]{0.3300,0.3300,0.2100,0.2100,-0.2100,-0.2100,-0.3300,-0.3300,-0.4100,0.4100,0.4100,0.5700,0.5700,0.4100,0.4100,-0.4100,}
-64.978 LMS_LASER_2D_RIGHT LMS2 ID=4151,time=1225719876.628322,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=240,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.157,23.148,16.790,13.704,11.448,10.109,9.200,8.368,7.599,6.976,6.408,5.971,5.568,5.246,4.908,4.571,4.330,4.108,3.942,3.744,3.579,3.389,3.207,3.110,2.963,2.847,2.738,2.631,2.551,2.479,2.397,2.319,2.248,2.200,2.121,2.068,1.986,1.944,1.871,1.812,1.797,1.762,1.714,1.633,1.603,1.584,1.554,1.537,1.495,1.463,1.441,1.422,1.381,1.355,1.322,1.304,1.288,1.260,1.242,1.217,1.210,1.191,1.165,1.151,1.140,1.137,1.112,1.103,1.081,1.080,1.080,1.070,1.076,1.093,1.093,1.095,1.098,1.101,1.106,1.093,1.089,1.086,1.077,1.051,1.048,1.034,1.027,1.027,1.017,1.016,1.004},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,7.000,5.000,91.000,118.000,96.000,72.000,57.000,56.000,55.000,60.000,65.000,65.000,66.000,67.000,70.000,71.000,72.000,74.000,75.000,77.000,78.000,76.000,77.000,78.000,79.000,80.000,80.000,80.000,80.000,78.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,80.000,78.000,70.000,66.000,65.000,73.000,77.000,75.000,76.000,77.000,72.000,64.000,65.000,71.000,71.000,71.000,71.000,70.000,72.000,73.000,69.000,68.000,73.000,70.000,64.000,59.000,65.000,70.000,69.000,67.000,66.000,58.000,47.000,43.000,42.000,36.000,33.000,52.000,58.000,57.000,55.000,51.000,54.000,57.000,58.000,55.000,55.000,47.000,43.000,49.000}
-64.978 LMS_LASER_2D_LEFT LMS1 ID=4278,time=1225719876.622786,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=19,Range=[181]{1.031,1.042,1.042,1.051,1.060,1.073,1.077,1.093,1.099,1.106,1.113,1.133,1.143,1.155,1.160,1.171,1.190,1.214,1.224,1.229,1.249,1.268,1.271,1.290,1.307,1.320,1.336,1.359,1.374,1.398,1.416,1.443,1.444,1.484,1.491,1.533,1.567,1.595,1.608,1.630,1.662,1.681,1.708,1.752,1.772,1.784,1.809,1.874,1.935,1.969,2.008,2.050,2.092,2.156,2.194,2.236,2.268,2.374,2.435,2.496,2.541,2.553,2.545,2.601,2.723,2.763,2.821,2.890,2.971,3.132,3.230,3.321,3.427,3.569,3.625,3.794,3.838,3.878,3.871,3.862,3.882,3.913,3.920,3.929,3.933,3.929,3.949,3.945,3.933,3.966,4.005,4.030,4.038,4.044,4.084,4.085,4.085,4.087,4.086,4.078,4.083,4.081,4.081,4.078,4.085,4.087,4.096,4.104,4.104,4.114,4.122,4.122,4.131,4.146,4.152,4.161,4.170,4.168,4.191,4.195,4.195,4.213,4.223,4.242,4.252,4.257,4.275,4.286,4.300,4.315,4.332,4.341,4.357,4.376,4.385,4.400,4.420,4.447,4.469,4.485,4.503,4.521,4.536,4.545,4.567,4.594,4.609,4.636,4.658,4.684,4.704,4.728,4.753,4.779,4.805,4.837,4.863,4.902,4.926,4.948,4.987,5.009,4.173,4.085,4.224,4.133,4.162,4.146,4.319,4.441,4.317,2.270,2.240,4.197,4.214,2.311,2.483,2.471,2.463,2.388,2.480},Reflectance=[181]{43.000,45.000,41.000,44.000,41.000,45.000,44.000,45.000,47.000,43.000,42.000,43.000,44.000,44.000,41.000,42.000,43.000,45.000,46.000,44.000,46.000,46.000,43.000,44.000,45.000,50.000,53.000,51.000,50.000,46.000,38.000,35.000,30.000,32.000,29.000,33.000,47.000,52.000,54.000,56.000,54.000,54.000,58.000,55.000,56.000,63.000,60.000,53.000,45.000,46.000,55.000,55.000,51.000,45.000,43.000,57.000,59.000,55.000,55.000,47.000,55.000,61.000,64.000,58.000,52.000,53.000,56.000,49.000,47.000,49.000,46.000,58.000,58.000,52.000,57.000,61.000,67.000,53.000,54.000,61.000,72.000,74.000,75.000,75.000,74.000,73.000,74.000,73.000,72.000,69.000,71.000,75.000,77.000,74.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,80.000,79.000,79.000,79.000,79.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,80.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,78.000,77.000,76.000,77.000,76.000,91.000,75.000,95.000,81.000,95.000,83.000,90.000,90.000,5.000,48.000,30.000,75.000,75.000,94.000,78.000,80.000,80.000,80.000,78.000}
-64.990 LMS_LASER_2D_RIGHT LMS2 ID=4152,time=1225719876.641654,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=241,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.269,-1.000,16.725,13.671,11.436,10.066,9.178,8.357,7.618,7.001,6.417,5.980,5.586,5.264,4.899,4.579,4.331,4.110,3.924,3.733,3.559,3.369,3.203,3.113,2.962,2.845,2.738,2.652,2.533,2.468,2.373,2.318,2.255,2.198,2.130,2.039,1.978,1.935,1.839,1.812,1.795,1.762,1.716,1.654,1.625,1.591,1.567,1.530,1.498,1.448,1.432,1.405,1.384,1.357,1.322,1.305,1.280,1.261,1.243,1.226,1.215,1.195,1.170,1.164,1.153,1.122,1.097,1.100,1.083,1.082,1.072,1.071,1.076,1.095,1.100,1.101,1.090,1.100,1.115,1.091,1.083,1.072,1.066,1.048,1.042,1.036,1.029,1.030,1.011,1.000,0.999},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,0.000,90.000,119.000,94.000,72.000,58.000,55.000,56.000,60.000,65.000,65.000,66.000,67.000,70.000,71.000,73.000,74.000,75.000,77.000,77.000,75.000,79.000,80.000,79.000,80.000,80.000,80.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,77.000,76.000,74.000,75.000,75.000,68.000,71.000,74.000,72.000,69.000,69.000,70.000,72.000,73.000,72.000,72.000,71.000,68.000,63.000,63.000,66.000,63.000,60.000,68.000,72.000,73.000,72.000,69.000,66.000,58.000,48.000,38.000,41.000,31.000,34.000,49.000,61.000,62.000,60.000,54.000,57.000,58.000,59.000,56.000,56.000,52.000,54.000,51.000}
-64.990 LMS_LASER_2D_LEFT LMS1 ID=4279,time=1225719876.636124,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=20,Range=[181]{1.025,1.036,1.048,1.049,1.068,1.076,1.079,1.084,1.097,1.113,1.116,1.129,1.144,1.156,1.171,1.177,1.197,1.213,1.212,1.233,1.254,1.268,1.267,1.293,1.318,1.317,1.342,1.367,1.379,1.399,1.407,1.426,1.444,1.480,1.512,1.539,1.566,1.591,1.608,1.624,1.657,1.680,1.708,1.734,1.769,1.807,1.841,1.884,1.927,1.967,2.007,2.040,2.098,2.148,2.209,2.240,2.267,2.379,2.429,2.497,2.552,2.554,2.545,2.603,2.713,2.757,2.818,2.892,2.962,3.120,3.239,3.330,3.420,3.583,3.634,3.803,3.841,3.871,3.870,3.854,3.872,3.911,3.921,3.929,3.933,3.932,3.949,3.942,3.934,3.967,4.008,4.030,4.024,4.045,4.084,4.079,4.078,4.088,4.087,4.078,4.069,4.078,4.076,4.085,4.085,4.097,4.101,4.104,4.109,4.114,4.122,4.122,4.131,4.140,4.149,4.161,4.168,4.168,4.182,4.197,4.200,4.215,4.222,4.232,4.250,4.257,4.278,4.287,4.301,4.313,4.331,4.341,4.358,4.376,4.385,4.402,4.419,4.448,4.469,4.485,4.494,4.524,4.530,4.548,4.567,4.594,4.609,4.636,4.659,4.686,4.702,4.726,4.753,4.779,4.803,4.839,4.865,4.902,4.923,4.949,4.985,5.009,4.224,4.125,4.211,4.129,4.234,4.142,4.275,4.383,4.459,4.444,4.257,4.177,4.224,2.568,2.491,2.470,2.354,2.361,2.479},Reflectance=[181]{44.000,44.000,45.000,40.000,45.000,45.000,44.000,44.000,43.000,46.000,43.000,42.000,44.000,43.000,45.000,44.000,46.000,45.000,41.000,43.000,48.000,46.000,50.000,50.000,45.000,41.000,52.000,51.000,45.000,46.000,42.000,32.000,29.000,30.000,43.000,38.000,51.000,54.000,54.000,57.000,56.000,54.000,58.000,55.000,54.000,55.000,55.000,53.000,50.000,49.000,51.000,54.000,46.000,49.000,49.000,58.000,58.000,53.000,56.000,52.000,56.000,62.000,63.000,59.000,51.000,55.000,58.000,49.000,47.000,47.000,46.000,58.000,59.000,54.000,53.000,64.000,67.000,54.000,57.000,63.000,71.000,73.000,76.000,75.000,74.000,74.000,74.000,74.000,72.000,69.000,71.000,75.000,76.000,75.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,76.000,95.000,83.000,92.000,83.000,96.000,87.000,85.000,88.000,93.000,96.000,83.000,75.000,80.000,83.000,78.000,79.000,82.000,80.000,77.000}
-65.007 DESIRED_THRUST iJoystick 86.60237434
-65.007 DESIRED_RUDDER iJoystick 0
-65.003 LMS_LASER_2D_LEFT LMS1 ID=4280,time=1225719876.649462,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=21,Range=[181]{1.032,1.033,1.038,1.057,1.062,1.074,1.074,1.096,1.098,1.102,1.119,1.133,1.139,1.149,1.164,1.186,1.190,1.201,1.211,1.236,1.244,1.262,1.282,1.284,1.310,1.318,1.346,1.360,1.380,1.397,1.410,1.421,1.441,1.468,1.514,1.538,1.566,1.579,1.608,1.625,1.661,1.680,1.717,1.741,1.778,1.820,1.849,1.876,1.937,1.963,2.005,2.049,2.105,2.156,2.195,2.232,2.278,2.378,2.425,2.483,2.541,2.554,2.545,2.596,2.704,2.760,2.788,2.885,2.971,3.121,3.236,3.325,3.421,3.577,3.664,3.803,3.837,3.873,3.866,3.854,3.878,3.913,3.921,3.930,3.926,3.932,3.950,3.942,3.935,3.962,4.004,4.030,4.023,4.044,4.076,4.079,4.078,4.077,4.087,4.079,4.079,4.078,4.076,4.086,4.087,4.096,4.096,4.099,4.104,4.112,4.121,4.122,4.131,4.141,4.150,4.163,4.168,4.168,4.176,4.192,4.199,4.215,4.223,4.240,4.251,4.259,4.276,4.285,4.301,4.313,4.332,4.341,4.358,4.376,4.385,4.403,4.420,4.447,4.467,4.488,4.494,4.521,4.533,4.546,4.566,4.594,4.610,4.636,4.659,4.678,4.705,4.730,4.755,4.781,4.803,4.838,4.866,4.890,4.924,4.950,4.974,5.008,4.331,4.085,4.147,4.169,4.350,4.133,4.202,4.308,4.366,4.406,4.217,4.193,4.256,2.668,2.489,2.337,2.232,2.471,2.481},Reflectance=[181]{43.000,44.000,43.000,47.000,44.000,47.000,43.000,46.000,46.000,44.000,44.000,40.000,43.000,39.000,43.000,45.000,43.000,43.000,40.000,43.000,47.000,43.000,49.000,49.000,46.000,33.000,45.000,52.000,49.000,49.000,40.000,29.000,29.000,29.000,34.000,50.000,54.000,56.000,54.000,54.000,54.000,54.000,54.000,54.000,54.000,53.000,50.000,54.000,46.000,47.000,50.000,51.000,46.000,45.000,51.000,59.000,55.000,53.000,58.000,57.000,55.000,62.000,63.000,60.000,51.000,56.000,66.000,50.000,47.000,48.000,48.000,56.000,59.000,56.000,50.000,64.000,66.000,51.000,55.000,62.000,71.000,74.000,76.000,76.000,75.000,74.000,74.000,74.000,72.000,68.000,70.000,75.000,76.000,74.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,77.000,76.000,77.000,77.000,77.000,77.000,76.000,76.000,97.000,78.000,80.000,93.000,100.000,86.000,74.000,81.000,88.000,94.000,79.000,74.000,81.000,131.000,78.000,83.000,78.000,80.000,78.000}
-65.015 LMS_LASER_2D_RIGHT LMS2 ID=4153,time=1225719876.654999,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=242,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.284,23.116,16.768,13.542,11.346,10.030,9.144,8.363,7.579,6.976,6.392,5.954,5.568,5.211,4.863,4.571,4.331,4.108,3.916,3.726,3.540,3.330,3.208,3.100,2.944,2.836,2.743,2.653,2.553,2.461,2.374,2.327,2.246,2.192,2.114,2.004,1.961,1.927,1.858,1.812,1.768,1.741,1.707,1.648,1.622,1.596,1.563,1.512,1.455,1.438,1.424,1.411,1.379,1.359,1.322,1.304,1.286,1.260,1.243,1.224,1.226,1.213,1.183,1.173,1.147,1.145,1.114,1.099,1.089,1.081,1.072,1.071,1.079,1.087,1.095,1.095,1.091,1.104,1.110,1.091,1.085,1.071,1.072,1.056,1.037,1.027,1.031,1.029,1.021,1.001,0.986},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,13.000,8.000,93.000,119.000,94.000,70.000,58.000,54.000,54.000,60.000,66.000,66.000,66.000,69.000,71.000,71.000,73.000,73.000,75.000,74.000,76.000,74.000,78.000,78.000,78.000,80.000,78.000,80.000,81.000,81.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,78.000,78.000,78.000,77.000,75.000,70.000,70.000,74.000,75.000,74.000,72.000,69.000,70.000,68.000,71.000,72.000,69.000,57.000,55.000,61.000,60.000,66.000,64.000,69.000,72.000,70.000,70.000,68.000,66.000,60.000,52.000,45.000,37.000,33.000,33.000,36.000,53.000,55.000,56.000,52.000,57.000,59.000,59.000,57.000,56.000,49.000,55.000,60.000}
-65.015 LMS_LASER_2D_LEFT LMS1 ID=4281,time=1225719876.662798,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=22,Range=[181]{1.030,1.045,1.040,1.059,1.064,1.073,1.074,1.091,1.102,1.114,1.122,1.129,1.144,1.148,1.168,1.183,1.191,1.203,1.227,1.236,1.249,1.264,1.269,1.290,1.306,1.318,1.346,1.360,1.375,1.400,1.406,1.428,1.441,1.463,1.511,1.541,1.556,1.579,1.608,1.638,1.663,1.689,1.708,1.750,1.779,1.823,1.849,1.887,1.932,1.971,2.005,2.057,2.102,2.153,2.213,2.241,2.317,2.385,2.428,2.488,2.548,2.552,2.545,2.602,2.701,2.770,2.793,2.884,2.983,3.133,3.247,3.330,3.429,3.588,3.675,3.820,3.854,3.873,3.870,3.845,3.879,3.913,3.920,3.929,3.926,3.931,3.950,3.939,3.935,3.970,4.001,4.031,4.024,4.045,4.077,4.078,4.078,4.075,4.086,4.077,4.067,4.074,4.075,4.077,4.087,4.095,4.099,4.109,4.104,4.112,4.122,4.122,4.132,4.140,4.148,4.158,4.167,4.168,4.174,4.192,4.200,4.208,4.226,4.233,4.250,4.258,4.274,4.286,4.300,4.323,4.331,4.341,4.358,4.367,4.385,4.401,4.419,4.446,4.466,4.485,4.494,4.521,4.530,4.547,4.566,4.593,4.608,4.626,4.656,4.678,4.704,4.728,4.754,4.781,4.804,4.840,4.870,4.889,4.925,4.951,4.976,5.009,4.243,4.094,4.118,4.178,4.237,4.160,4.223,4.287,4.304,4.346,4.193,4.235,4.301,2.615,2.389,2.194,2.286,2.468,2.479},Reflectance=[181]{38.000,45.000,43.000,45.000,46.000,50.000,43.000,47.000,45.000,43.000,45.000,42.000,44.000,43.000,47.000,47.000,46.000,44.000,47.000,48.000,49.000,52.000,51.000,52.000,48.000,41.000,45.000,48.000,50.000,46.000,32.000,31.000,29.000,28.000,37.000,51.000,54.000,56.000,54.000,55.000,55.000,54.000,54.000,54.000,51.000,51.000,47.000,51.000,48.000,50.000,54.000,47.000,45.000,43.000,51.000,55.000,54.000,56.000,60.000,59.000,54.000,60.000,66.000,58.000,53.000,56.000,67.000,53.000,49.000,45.000,49.000,55.000,59.000,56.000,51.000,63.000,61.000,51.000,57.000,64.000,71.000,74.000,75.000,75.000,75.000,74.000,74.000,73.000,72.000,68.000,69.000,75.000,76.000,75.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,76.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,76.000,97.000,78.000,77.000,94.000,99.000,87.000,70.000,79.000,80.000,91.000,74.000,80.000,85.000,82.000,81.000,72.000,83.000,79.000,77.000}
-65.023 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.8683,20.6804,-0.9397},Vel=[3x1]{-0.7616,-0.5566,-5.6410},Raw=[2x1]{23.4043,-0.9397},time=1225719876.67058277130127,Speed=0.94331357144943,Pitch=0.01346012240303,Roll=0.02692024480606,PitchDot=-0.00224335373384,RollDot=0.00029163598540
-65.023 ODOMETRY_POSE iPlatform Pose=[3x1]{6.8683,20.6804,-0.9393},Vel=[3x1]{-0.7616,-0.5566,0.6422},Raw=[2x1]{23.4043,-0.9397},time=1225719876.6706,Speed=0.9433,Pitch=-0.0138,Roll=0.0268,PitchDot=-0.0016,RollDot=0.0016
-65.026 LMS_LASER_2D_RIGHT LMS2 ID=4154,time=1225719876.668340,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=243,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.209,-1.000,16.386,13.435,11.223,9.972,9.076,8.335,7.544,6.930,6.192,5.928,5.560,5.201,4.837,4.551,4.301,4.100,3.891,3.708,3.528,3.355,3.210,3.082,2.949,2.839,2.741,2.633,2.542,2.452,2.365,2.319,2.237,2.181,2.110,2.010,1.966,1.924,1.888,1.821,1.770,1.735,1.689,1.659,1.624,1.601,1.554,1.477,1.445,1.440,1.437,1.412,1.387,1.360,1.335,1.304,1.283,1.250,1.218,1.216,1.213,1.204,1.189,1.168,1.145,1.130,1.113,1.105,1.081,1.074,1.064,1.072,1.079,1.084,1.092,1.101,1.091,1.095,1.084,1.099,1.087,1.072,1.065,1.058,1.038,1.036,1.034,1.024,1.019,1.009,0.978},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,19.000,0.000,102.000,118.000,94.000,69.000,58.000,53.000,55.000,60.000,69.000,66.000,66.000,68.000,70.000,71.000,73.000,74.000,76.000,74.000,76.000,76.000,78.000,76.000,78.000,78.000,78.000,80.000,80.000,81.000,81.000,80.000,80.000,80.000,79.000,80.000,79.000,79.000,79.000,79.000,80.000,80.000,79.000,78.000,79.000,77.000,72.000,74.000,75.000,77.000,78.000,78.000,76.000,76.000,74.000,70.000,64.000,69.000,74.000,70.000,59.000,55.000,56.000,54.000,63.000,66.000,67.000,69.000,70.000,71.000,70.000,67.000,60.000,51.000,47.000,43.000,38.000,35.000,30.000,41.000,52.000,57.000,57.000,54.000,53.000,52.000,54.000,53.000,44.000,47.000,56.000}
-65.031 DESIRED_THRUST iJoystick 86.60237434
-65.031 DESIRED_RUDDER iJoystick 0
-65.039 LMS_LASER_2D_RIGHT LMS2 ID=4155,time=1225719876.681682,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=244,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.035,-1.000,16.139,13.331,11.163,9.867,8.970,8.231,7.453,6.837,6.074,5.877,5.518,5.183,4.808,4.534,4.267,4.066,3.868,3.704,3.513,3.334,3.183,3.074,2.942,2.825,2.713,2.607,2.523,2.441,2.372,2.310,2.227,2.165,2.110,2.014,1.973,1.924,1.861,1.821,1.777,1.740,1.697,1.662,1.623,1.593,1.545,1.472,1.446,1.437,1.433,1.406,1.382,1.357,1.331,1.303,1.269,1.243,1.227,1.217,1.204,1.196,1.188,1.162,1.149,1.128,1.106,1.091,1.077,1.079,1.073,1.071,1.076,1.079,1.084,1.080,1.084,1.095,1.091,1.084,1.095,1.073,1.062,1.060,1.049,1.028,1.029,1.032,1.014,1.001,0.982},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,26.000,0.000,104.000,113.000,95.000,67.000,57.000,52.000,54.000,64.000,71.000,67.000,67.000,68.000,70.000,70.000,74.000,74.000,77.000,75.000,77.000,76.000,78.000,75.000,78.000,71.000,77.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,79.000,78.000,79.000,80.000,79.000,79.000,79.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,75.000,69.000,69.000,69.000,72.000,73.000,71.000,64.000,65.000,64.000,63.000,61.000,64.000,69.000,73.000,74.000,75.000,70.000,66.000,58.000,56.000,54.000,52.000,47.000,40.000,33.000,32.000,42.000,53.000,60.000,58.000,53.000,60.000,56.000,43.000,38.000,51.000,58.000}
-65.039 LMS_LASER_2D_LEFT LMS1 ID=4282,time=1225719876.676145,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=23,Range=[181]{1.031,1.038,1.048,1.049,1.059,1.075,1.075,1.090,1.105,1.110,1.126,1.131,1.138,1.153,1.169,1.173,1.192,1.209,1.218,1.236,1.250,1.263,1.277,1.291,1.316,1.322,1.345,1.357,1.375,1.400,1.417,1.422,1.450,1.470,1.520,1.536,1.565,1.592,1.616,1.635,1.659,1.688,1.720,1.744,1.787,1.821,1.848,1.897,1.932,1.983,2.013,2.055,2.098,2.160,2.211,2.258,2.305,2.359,2.422,2.487,2.540,2.552,2.545,2.603,2.701,2.759,2.805,2.873,2.985,3.136,3.248,3.330,3.468,3.588,3.689,3.837,3.868,3.873,3.871,3.854,3.878,3.915,3.921,3.929,3.933,3.928,3.958,3.941,3.940,3.959,4.011,4.028,4.024,4.053,4.076,4.078,4.077,4.084,4.084,4.079,4.078,4.079,4.078,4.077,4.084,4.086,4.096,4.101,4.112,4.116,4.122,4.122,4.131,4.141,4.149,4.158,4.166,4.167,4.183,4.189,4.205,4.215,4.223,4.241,4.250,4.256,4.274,4.286,4.304,4.322,4.332,4.347,4.358,4.376,4.385,4.401,4.427,4.447,4.466,4.484,4.503,4.521,4.530,4.546,4.566,4.592,4.606,4.636,4.661,4.681,4.704,4.730,4.756,4.778,4.812,4.839,4.866,4.897,4.925,4.951,4.977,5.008,4.196,4.044,4.143,4.229,4.216,4.214,4.229,4.288,4.287,4.278,4.227,4.297,4.330,2.416,2.235,2.232,2.467,2.470,2.478},Reflectance=[181]{43.000,39.000,47.000,43.000,41.000,47.000,43.000,46.000,45.000,44.000,47.000,43.000,42.000,41.000,48.000,43.000,47.000,47.000,51.000,48.000,46.000,48.000,50.000,49.000,48.000,51.000,53.000,54.000,46.000,46.000,35.000,30.000,29.000,29.000,37.000,53.000,54.000,54.000,54.000,58.000,57.000,58.000,55.000,55.000,54.000,50.000,46.000,48.000,48.000,48.000,53.000,50.000,46.000,47.000,46.000,54.000,56.000,57.000,61.000,59.000,55.000,60.000,65.000,59.000,53.000,56.000,68.000,56.000,50.000,47.000,50.000,47.000,48.000,52.000,49.000,57.000,56.000,51.000,57.000,64.000,71.000,74.000,76.000,75.000,74.000,73.000,74.000,74.000,71.000,67.000,70.000,75.000,76.000,74.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,77.000,76.000,94.000,69.000,84.000,100.000,96.000,90.000,72.000,77.000,79.000,79.000,77.000,86.000,88.000,58.000,84.000,80.000,80.000,79.000,77.000}
-65.050 LMS_LASER_2D_RIGHT LMS2 ID=4156,time=1225719876.695021,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=245,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.955,18.754,15.640,12.945,10.913,9.785,8.884,8.147,7.410,6.268,6.026,5.821,5.449,5.137,4.765,4.508,4.247,4.038,3.839,3.665,3.486,3.309,3.147,3.046,2.907,2.791,2.702,2.598,2.513,2.433,2.362,2.292,2.227,2.156,2.100,2.018,1.964,1.920,1.855,1.830,1.785,1.732,1.688,1.662,1.622,1.587,1.548,1.478,1.455,1.434,1.424,1.393,1.366,1.353,1.329,1.304,1.261,1.244,1.218,1.213,1.198,1.173,1.157,1.147,1.129,1.114,1.099,1.091,1.077,1.065,1.064,1.064,1.063,1.060,1.067,1.072,1.069,1.069,1.077,1.091,1.083,1.070,1.070,1.058,1.044,1.037,1.031,1.032,1.023,0.994,0.997},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,26.000,14.000,114.000,110.000,90.000,65.000,58.000,53.000,54.000,77.000,69.000,67.000,67.000,69.000,70.000,70.000,73.000,75.000,75.000,77.000,77.000,76.000,78.000,78.000,78.000,72.000,79.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,77.000,78.000,78.000,79.000,80.000,79.000,79.000,79.000,79.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,75.000,76.000,74.000,67.000,70.000,71.000,73.000,73.000,75.000,67.000,69.000,70.000,67.000,65.000,69.000,72.000,76.000,74.000,72.000,69.000,69.000,68.000,64.000,58.000,57.000,63.000,63.000,63.000,53.000,50.000,52.000,56.000,57.000,55.000,56.000,53.000,38.000,46.000,52.000,53.000}
-65.050 LMS_LASER_2D_LEFT LMS1 ID=4283,time=1225719876.689489,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=24,Range=[181]{1.025,1.038,1.054,1.055,1.061,1.080,1.078,1.096,1.103,1.116,1.127,1.131,1.141,1.158,1.166,1.177,1.197,1.212,1.224,1.235,1.246,1.273,1.278,1.289,1.310,1.322,1.340,1.360,1.379,1.401,1.408,1.432,1.453,1.478,1.526,1.530,1.556,1.577,1.613,1.627,1.658,1.689,1.724,1.750,1.778,1.813,1.860,1.895,1.930,1.978,2.015,2.064,2.116,2.160,2.216,2.260,2.303,2.365,2.421,2.498,2.551,2.554,2.545,2.608,2.719,2.780,2.818,2.884,3.020,3.173,3.261,3.341,3.480,3.597,3.715,3.853,3.883,3.867,3.855,3.854,3.880,3.914,3.919,3.929,3.931,3.929,3.955,3.936,3.939,3.976,4.014,4.031,4.024,4.053,4.077,4.077,4.078,4.085,4.083,4.078,4.076,4.074,4.078,4.079,4.087,4.092,4.099,4.104,4.113,4.116,4.114,4.122,4.131,4.143,4.149,4.158,4.167,4.168,4.186,4.195,4.205,4.213,4.229,4.240,4.248,4.267,4.276,4.285,4.307,4.323,4.330,4.349,4.361,4.379,4.395,4.398,4.424,4.458,4.466,4.485,4.502,4.521,4.539,4.555,4.574,4.593,4.609,4.633,4.659,4.680,4.707,4.738,4.755,4.779,4.813,4.841,4.873,4.899,4.923,4.952,4.986,5.011,4.142,4.064,4.150,4.200,4.177,4.231,4.259,4.325,4.314,4.249,4.293,4.409,5.401,2.174,2.233,2.460,2.474,2.468,2.477},Reflectance=[181]{44.000,43.000,46.000,46.000,42.000,46.000,42.000,45.000,49.000,47.000,48.000,46.000,47.000,45.000,43.000,44.000,45.000,44.000,50.000,47.000,48.000,49.000,51.000,48.000,49.000,51.000,51.000,48.000,48.000,47.000,43.000,32.000,30.000,30.000,41.000,54.000,54.000,55.000,56.000,55.000,56.000,58.000,54.000,54.000,54.000,54.000,47.000,51.000,55.000,49.000,54.000,50.000,46.000,47.000,52.000,55.000,55.000,60.000,61.000,56.000,56.000,61.000,65.000,61.000,50.000,57.000,67.000,58.000,46.000,47.000,48.000,48.000,45.000,49.000,53.000,57.000,55.000,52.000,58.000,64.000,71.000,74.000,75.000,75.000,74.000,73.000,73.000,72.000,71.000,67.000,71.000,75.000,76.000,74.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,79.000,79.000,79.000,77.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,79.000,79.000,79.000,77.000,77.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,89.000,75.000,92.000,98.000,93.000,79.000,76.000,77.000,82.000,78.000,82.000,91.000,64.000,69.000,80.000,79.000,80.000,79.000,77.000}
-65.055 DESIRED_THRUST iJoystick 86.60237434
-65.055 DESIRED_RUDDER iJoystick 0
-65.059 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.8914,20.6973,-0.9387},Vel=[3x1]{-0.7693,-0.5634,-0.3846},Raw=[2x1]{23.4328,-0.9387},time=1225719876.70657873153687,Speed=0.95353523553635,Pitch=0.01346012240303,Roll=0.02692024480606,PitchDot=-0.00448670746768,RollDot=0.00011216768669
-65.059 ODOMETRY_POSE iPlatform Pose=[3x1]{6.8914,20.6973,-0.9383},Vel=[3x1]{-0.7693,-0.5634,-0.3846},Raw=[2x1]{23.4328,-0.9387},time=1225719876.7066,Speed=0.9535,Pitch=-0.0138,Roll=0.0268,PitchDot=-0.0042,RollDot=-0.0016
-65.063 LMS_LASER_2D_LEFT LMS1 ID=4284,time=1225719876.702833,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=25,Range=[181]{1.033,1.017,1.045,1.053,1.063,1.070,1.084,1.093,1.097,1.119,1.122,1.131,1.144,1.163,1.178,1.191,1.200,1.208,1.230,1.242,1.254,1.263,1.283,1.298,1.310,1.331,1.347,1.368,1.383,1.406,1.427,1.444,1.456,1.478,1.525,1.553,1.567,1.598,1.620,1.629,1.662,1.691,1.734,1.750,1.783,1.821,1.860,1.910,1.945,1.982,2.021,2.073,2.125,2.165,2.219,2.256,2.309,2.379,2.422,2.522,2.558,2.553,2.554,2.628,2.723,2.781,2.841,2.941,3.044,3.181,3.276,3.358,3.479,3.605,3.742,3.862,3.880,3.870,3.845,3.858,3.890,3.916,3.929,3.936,3.926,3.935,3.954,3.933,3.939,3.977,4.020,4.031,4.019,4.071,4.076,4.076,4.077,4.084,4.090,4.076,4.077,4.083,4.084,4.088,4.087,4.096,4.100,4.102,4.113,4.116,4.128,4.122,4.131,4.139,4.150,4.158,4.167,4.176,4.188,4.195,4.204,4.221,4.230,4.241,4.249,4.266,4.277,4.292,4.308,4.323,4.341,4.349,4.366,4.376,4.395,4.410,4.434,4.457,4.475,4.494,4.501,4.521,4.536,4.555,4.575,4.599,4.617,4.642,4.660,4.688,4.714,4.737,4.763,4.786,4.811,4.848,4.873,4.908,4.925,4.959,4.995,4.998,4.143,4.060,4.147,4.199,4.175,4.217,4.321,4.338,4.373,4.261,4.469,4.357,5.401,2.381,2.470,2.471,2.470,2.474,2.484},Reflectance=[181]{37.000,30.000,33.000,38.000,43.000,42.000,44.000,41.000,43.000,45.000,43.000,43.000,44.000,45.000,48.000,46.000,47.000,45.000,49.000,46.000,48.000,48.000,53.000,48.000,49.000,47.000,50.000,51.000,50.000,49.000,47.000,34.000,29.000,28.000,40.000,49.000,51.000,54.000,55.000,59.000,58.000,59.000,51.000,54.000,56.000,57.000,54.000,53.000,46.000,55.000,50.000,46.000,47.000,49.000,45.000,58.000,58.000,62.000,62.000,55.000,55.000,61.000,66.000,61.000,48.000,58.000,63.000,49.000,45.000,46.000,50.000,48.000,45.000,48.000,58.000,57.000,54.000,53.000,63.000,67.000,72.000,75.000,75.000,75.000,75.000,72.000,73.000,72.000,71.000,67.000,72.000,75.000,75.000,74.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,80.000,79.000,79.000,78.000,77.000,78.000,78.000,79.000,80.000,79.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,79.000,79.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,75.000,87.000,76.000,97.000,97.000,92.000,79.000,78.000,75.000,91.000,79.000,90.000,91.000,63.000,69.000,77.000,80.000,79.000,79.000,77.000}
-65.063 LMS_LASER_2D_RIGHT LMS2 ID=4157,time=1225719876.708360,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=246,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.522,17.958,15.204,12.564,10.627,9.617,8.711,7.989,7.269,6.223,6.035,5.741,5.397,5.075,4.689,4.456,4.230,3.983,3.788,3.620,3.440,3.263,3.139,3.030,2.902,2.794,2.670,2.557,2.485,2.424,2.345,2.274,2.183,2.131,2.084,2.007,1.936,1.884,1.841,1.797,1.760,1.715,1.689,1.656,1.605,1.578,1.539,1.498,1.477,1.454,1.424,1.388,1.361,1.341,1.303,1.280,1.258,1.236,1.210,1.200,1.191,1.173,1.154,1.136,1.122,1.107,1.091,1.083,1.079,1.074,1.064,1.057,1.056,1.055,1.068,1.060,1.069,1.069,1.070,1.087,1.073,1.057,1.055,1.045,1.038,1.036,1.027,1.015,1.014,1.009,0.991},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,33.000,56.000,110.000,108.000,85.000,61.000,58.000,53.000,56.000,74.000,68.000,67.000,66.000,69.000,71.000,71.000,73.000,74.000,75.000,77.000,77.000,78.000,79.000,78.000,79.000,77.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,78.000,80.000,77.000,74.000,76.000,79.000,80.000,78.000,78.000,77.000,76.000,77.000,78.000,77.000,74.000,74.000,72.000,69.000,73.000,75.000,74.000,73.000,72.000,70.000,68.000,64.000,63.000,69.000,72.000,74.000,73.000,75.000,71.000,70.000,72.000,70.000,68.000,62.000,63.000,64.000,63.000,56.000,35.000,53.000,57.000,56.000,60.000,60.000,55.000,51.000,38.000,36.000,47.000,50.000}
-65.074 LMS_LASER_2D_RIGHT LMS2 ID=4158,time=1225719876.721697,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=247,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.304,14.547,11.968,10.304,9.434,8.559,7.770,7.111,6.588,6.025,5.654,5.299,4.981,4.621,4.402,4.160,3.930,3.753,3.599,3.390,3.245,3.119,2.980,2.870,2.767,2.661,2.546,2.478,2.415,2.329,2.246,2.147,2.130,2.076,2.000,1.933,1.869,1.776,1.758,1.745,1.711,1.671,1.638,1.605,1.568,1.527,1.493,1.465,1.443,1.416,1.379,1.360,1.329,1.296,1.271,1.243,1.234,1.208,1.192,1.174,1.153,1.145,1.132,1.122,1.117,1.099,1.088,1.080,1.079,1.072,1.055,1.062,1.066,1.077,1.081,1.093,1.091,1.088,1.068,1.077,1.062,1.052,1.034,1.038,1.026,1.026,1.022,1.015,0.989,0.984},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,78.000,114.000,107.000,79.000,58.000,58.000,56.000,60.000,64.000,67.000,66.000,67.000,70.000,71.000,72.000,74.000,74.000,75.000,76.000,74.000,78.000,78.000,77.000,80.000,80.000,80.000,79.000,81.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,74.000,76.000,78.000,78.000,79.000,80.000,78.000,78.000,76.000,77.000,78.000,77.000,77.000,73.000,74.000,67.000,71.000,74.000,72.000,70.000,70.000,71.000,70.000,58.000,63.000,70.000,75.000,73.000,72.000,68.000,68.000,66.000,68.000,69.000,66.000,61.000,51.000,49.000,44.000,46.000,42.000,39.000,44.000,52.000,51.000,54.000,56.000,58.000,54.000,52.000,47.000,50.000,51.000}
-65.074 LMS_LASER_2D_LEFT LMS1 ID=4285,time=1225719876.716175,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=26,Range=[181]{1.031,1.042,1.025,1.060,1.062,1.071,1.093,1.097,1.103,1.130,1.126,1.128,1.152,1.160,1.169,1.192,1.208,1.219,1.224,1.241,1.253,1.271,1.296,1.301,1.320,1.331,1.346,1.368,1.384,1.407,1.433,1.448,1.459,1.482,1.532,1.557,1.569,1.612,1.617,1.644,1.671,1.692,1.741,1.762,1.788,1.820,1.866,1.910,1.950,1.989,2.033,2.081,2.134,2.178,2.233,2.279,2.331,2.388,2.431,2.537,2.552,2.545,2.572,2.680,2.732,2.789,2.864,2.954,3.065,3.200,3.292,3.385,3.492,3.614,3.753,3.862,3.882,3.862,3.854,3.858,3.894,3.920,3.929,3.926,3.934,3.936,3.945,3.925,3.942,3.986,4.023,4.031,4.027,4.086,4.078,4.078,4.076,4.092,4.082,4.077,4.078,4.081,4.078,4.087,4.086,4.093,4.103,4.105,4.111,4.116,4.122,4.122,4.131,4.143,4.154,4.150,4.167,4.183,4.186,4.194,4.207,4.222,4.230,4.239,4.256,4.266,4.275,4.289,4.311,4.323,4.341,4.357,4.375,4.385,4.392,4.415,4.441,4.458,4.476,4.492,4.512,4.530,4.537,4.554,4.582,4.601,4.618,4.643,4.668,4.690,4.722,4.738,4.771,4.797,4.823,4.854,4.889,4.913,4.940,4.969,5.001,4.382,4.144,4.048,4.144,4.208,4.174,4.316,4.348,4.326,4.361,4.304,5.410,4.219,5.398,2.503,2.483,2.475,2.474,2.475,2.491},Reflectance=[181]{39.000,33.000,30.000,41.000,44.000,42.000,45.000,43.000,41.000,46.000,44.000,41.000,44.000,44.000,48.000,47.000,46.000,48.000,50.000,50.000,51.000,48.000,47.000,44.000,54.000,47.000,49.000,51.000,50.000,50.000,46.000,35.000,29.000,29.000,43.000,50.000,41.000,52.000,54.000,54.000,58.000,56.000,50.000,55.000,55.000,57.000,53.000,50.000,49.000,54.000,55.000,46.000,47.000,47.000,40.000,55.000,56.000,62.000,64.000,53.000,60.000,65.000,61.000,52.000,55.000,62.000,56.000,47.000,46.000,47.000,46.000,48.000,45.000,48.000,59.000,57.000,55.000,61.000,62.000,67.000,73.000,75.000,75.000,75.000,75.000,72.000,73.000,72.000,70.000,68.000,73.000,75.000,74.000,76.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,77.000,76.000,77.000,77.000,76.000,96.000,87.000,78.000,94.000,98.000,92.000,84.000,78.000,77.000,93.000,80.000,63.000,14.000,60.000,75.000,79.000,80.000,80.000,79.000,76.000}
-65.079 DESIRED_THRUST iJoystick 86.60237434
-65.079 DESIRED_RUDDER iJoystick 0
-65.086 LMS_LASER_2D_RIGHT LMS2 ID=4159,time=1225719876.735033,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=248,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.943,13.766,11.439,9.998,9.206,8.356,7.580,6.948,6.442,5.946,5.543,5.236,4.881,4.571,4.357,4.091,3.885,3.732,3.494,3.328,3.217,3.068,2.954,2.851,2.738,2.642,2.539,2.461,2.388,2.318,2.192,2.141,2.121,2.058,1.977,1.941,1.812,1.768,1.759,1.738,1.706,1.654,1.635,1.580,1.542,1.512,1.488,1.463,1.431,1.404,1.387,1.364,1.319,1.297,1.269,1.250,1.225,1.207,1.198,1.171,1.154,1.141,1.127,1.118,1.108,1.097,1.095,1.085,1.078,1.071,1.060,1.060,1.068,1.073,1.081,1.082,1.092,1.072,1.067,1.078,1.073,1.059,1.044,1.036,1.018,1.017,1.015,1.008,0.998,0.988},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,89.000,122.000,99.000,72.000,56.000,55.000,55.000,60.000,64.000,67.000,67.000,67.000,71.000,71.000,72.000,74.000,73.000,76.000,74.000,73.000,78.000,79.000,79.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,79.000,76.000,74.000,79.000,78.000,76.000,80.000,79.000,76.000,76.000,75.000,78.000,78.000,76.000,76.000,74.000,65.000,65.000,73.000,70.000,68.000,70.000,68.000,68.000,65.000,64.000,71.000,77.000,77.000,74.000,68.000,65.000,63.000,64.000,66.000,64.000,63.000,55.000,50.000,46.000,36.000,36.000,32.000,30.000,39.000,46.000,47.000,51.000,52.000,59.000,62.000,57.000,50.000,50.000,49.000}
-65.087 LMS_LASER_2D_LEFT LMS1 ID=4286,time=1225719876.729517,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=27,Range=[181]{1.035,1.049,1.047,1.052,1.068,1.077,1.087,1.102,1.106,1.121,1.130,1.144,1.152,1.166,1.175,1.185,1.211,1.223,1.231,1.246,1.264,1.281,1.291,1.312,1.319,1.338,1.361,1.376,1.390,1.412,1.435,1.462,1.462,1.497,1.537,1.556,1.565,1.617,1.636,1.655,1.674,1.717,1.757,1.769,1.797,1.832,1.886,1.923,1.955,2.003,2.042,2.096,2.142,2.195,2.245,2.310,2.359,2.414,2.475,2.551,2.545,2.545,2.589,2.701,2.747,2.805,2.900,2.989,3.094,3.230,3.312,3.410,3.531,3.652,3.799,3.879,3.873,3.860,3.845,3.870,3.904,3.926,3.929,3.928,3.932,3.947,3.943,3.935,3.955,4.004,4.030,4.031,4.039,4.079,4.078,4.076,4.084,4.092,4.092,4.078,4.078,4.078,4.087,4.090,4.095,4.099,4.101,4.103,4.111,4.114,4.122,4.122,4.140,4.154,4.149,4.158,4.168,4.180,4.195,4.203,4.214,4.223,4.240,4.249,4.258,4.277,4.286,4.298,4.320,4.330,4.341,4.357,4.375,4.385,4.401,4.417,4.451,4.466,4.484,4.492,4.513,4.530,4.545,4.574,4.591,4.609,4.634,4.651,4.678,4.696,4.734,4.755,4.779,4.805,4.832,4.865,4.887,4.921,4.948,4.985,5.018,4.286,4.133,4.027,4.159,4.141,4.183,4.349,4.312,4.353,4.354,4.263,4.225,5.410,2.540,2.493,2.475,2.471,2.470,2.481,2.517},Reflectance=[181]{37.000,36.000,38.000,42.000,44.000,41.000,42.000,41.000,43.000,44.000,42.000,41.000,44.000,45.000,43.000,48.000,45.000,46.000,46.000,52.000,49.000,48.000,49.000,46.000,50.000,50.000,48.000,51.000,49.000,41.000,32.000,34.000,30.000,30.000,44.000,43.000,31.000,46.000,55.000,55.000,56.000,50.000,53.000,54.000,59.000,55.000,51.000,55.000,54.000,53.000,52.000,44.000,45.000,45.000,44.000,54.000,57.000,62.000,58.000,56.000,64.000,65.000,56.000,50.000,51.000,56.000,50.000,48.000,48.000,46.000,45.000,47.000,47.000,49.000,59.000,57.000,51.000,56.000,65.000,71.000,73.000,75.000,75.000,75.000,74.000,73.000,72.000,72.000,69.000,70.000,75.000,75.000,73.000,76.000,78.000,78.000,78.000,77.000,77.000,78.000,79.000,79.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,77.000,79.000,79.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,76.000,77.000,76.000,97.000,89.000,74.000,93.000,92.000,92.000,78.000,70.000,90.000,94.000,17.000,21.000,65.000,36.000,77.000,79.000,80.000,79.000,78.000,79.000}
-65.095 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.9220,20.7198,-0.9370},Vel=[3x1]{-0.7671,-0.5639,-3.0769},Raw=[2x1]{23.4708,-0.9370},time=1225719876.74256062507629,Speed=0.95207499780964,Pitch=0.01346012240303,Roll=0.02916359853990,PitchDot=-0.00897341493535,RollDot=0.00116654394160
-65.095 ODOMETRY_POSE iPlatform Pose=[3x1]{6.9220,20.7198,-0.9366},Vel=[3x1]{-0.7671,-0.5639,-3.0769},Raw=[2x1]{23.4708,-0.9370},time=1225719876.7426,Speed=0.9521,Pitch=-0.0155,Roll=0.0281,PitchDot=0.0089,RollDot=-0.0017
-65.098 LMS_LASER_2D_LEFT LMS1 ID=4287,time=1225719876.742856,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=28,Range=[181]{1.039,1.048,1.057,1.060,1.080,1.078,1.091,1.101,1.121,1.124,1.139,1.146,1.156,1.162,1.178,1.202,1.209,1.211,1.231,1.254,1.268,1.288,1.301,1.313,1.330,1.340,1.361,1.386,1.393,1.414,1.435,1.438,1.467,1.497,1.512,1.542,1.581,1.605,1.650,1.661,1.688,1.728,1.752,1.772,1.803,1.833,1.887,1.930,1.964,2.014,2.052,2.113,2.160,2.198,2.262,2.319,2.373,2.437,2.496,2.553,2.544,2.545,2.627,2.711,2.763,2.837,2.925,3.019,3.115,3.245,3.329,3.431,3.554,3.695,3.825,3.878,3.876,3.864,3.854,3.878,3.914,3.929,3.934,3.933,3.932,3.955,3.940,3.932,3.968,4.012,4.031,4.030,4.049,4.080,4.075,4.076,4.084,4.091,4.094,4.075,4.079,4.078,4.086,4.096,4.096,4.102,4.101,4.112,4.123,4.122,4.131,4.140,4.140,4.148,4.158,4.168,4.175,4.188,4.195,4.205,4.222,4.221,4.240,4.248,4.266,4.276,4.284,4.299,4.319,4.331,4.348,4.366,4.375,4.392,4.410,4.428,4.448,4.476,4.494,4.503,4.519,4.538,4.554,4.581,4.598,4.619,4.633,4.660,4.691,4.706,4.729,4.756,4.780,4.813,4.841,4.871,4.904,4.929,4.956,4.994,5.020,4.279,4.137,4.038,4.169,4.152,4.230,4.345,4.289,4.355,4.335,4.354,5.410,5.410,2.581,2.488,2.470,2.474,2.477,2.479,2.547},Reflectance=[181]{39.000,50.000,43.000,42.000,43.000,42.000,39.000,40.000,45.000,43.000,43.000,44.000,43.000,42.000,44.000,41.000,43.000,41.000,46.000,48.000,46.000,47.000,45.000,47.000,46.000,51.000,48.000,51.000,43.000,32.000,32.000,29.000,29.000,29.000,29.000,30.000,31.000,30.000,53.000,54.000,54.000,52.000,55.000,56.000,57.000,55.000,51.000,55.000,55.000,47.000,52.000,44.000,47.000,48.000,45.000,55.000,58.000,60.000,55.000,56.000,69.000,64.000,57.000,50.000,50.000,52.000,46.000,49.000,49.000,45.000,45.000,52.000,46.000,56.000,60.000,57.000,52.000,58.000,64.000,71.000,74.000,75.000,75.000,74.000,74.000,73.000,71.000,71.000,70.000,72.000,75.000,75.000,73.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,77.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,76.000,76.000,77.000,77.000,99.000,91.000,75.000,93.000,93.000,93.000,77.000,67.000,91.000,90.000,9.000,64.000,64.000,81.000,78.000,79.000,80.000,79.000,77.000,81.000}
-65.103 DESIRED_THRUST iJoystick 86.60237434
-65.103 DESIRED_RUDDER iJoystick 0
-65.111 LMS_LASER_2D_RIGHT LMS2 ID=4160,time=1225719876.748379,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=249,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.323,-1.000,16.100,13.225,11.039,9.812,8.962,8.182,7.437,6.790,6.330,5.859,5.468,5.164,4.766,4.500,4.292,4.026,3.830,3.690,3.421,3.298,3.183,3.027,2.925,2.816,2.731,2.631,2.524,2.457,2.364,2.291,2.176,2.142,2.093,2.027,1.967,1.913,1.824,1.789,1.755,1.719,1.689,1.665,1.621,1.572,1.546,1.498,1.478,1.449,1.423,1.399,1.378,1.343,1.313,1.305,1.270,1.241,1.234,1.223,1.198,1.172,1.162,1.138,1.117,1.108,1.100,1.081,1.081,1.072,1.063,1.062,1.060,1.056,1.063,1.068,1.081,1.078,1.089,1.088,1.046,1.034,1.071,1.071,1.052,1.039,1.032,1.020,1.013,1.008,0.994,0.985},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,0.000,108.000,115.000,94.000,65.000,57.000,53.000,55.000,61.000,64.000,67.000,67.000,68.000,72.000,71.000,72.000,74.000,75.000,77.000,74.000,76.000,78.000,77.000,78.000,78.000,80.000,80.000,80.000,80.000,81.000,80.000,81.000,81.000,80.000,80.000,80.000,78.000,78.000,78.000,76.000,63.000,77.000,80.000,75.000,74.000,77.000,76.000,77.000,77.000,76.000,77.000,71.000,62.000,70.000,72.000,61.000,68.000,70.000,66.000,68.000,67.000,64.000,67.000,73.000,73.000,72.000,69.000,69.000,68.000,68.000,66.000,64.000,61.000,53.000,55.000,49.000,35.000,38.000,35.000,28.000,27.000,34.000,45.000,51.000,53.000,50.000,52.000,48.000,51.000,48.000,52.000}
-65.111 LMS_LASER_2D_LEFT LMS1 ID=4288,time=1225719876.756195,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=29,Range=[181]{1.043,1.044,1.055,1.058,1.072,1.080,1.098,1.110,1.116,1.121,1.131,1.152,1.156,1.168,1.179,1.199,1.204,1.231,1.237,1.246,1.263,1.281,1.296,1.310,1.327,1.352,1.370,1.380,1.397,1.419,1.459,1.456,1.475,1.500,1.521,1.569,1.592,1.608,1.653,1.670,1.708,1.740,1.761,1.782,1.811,1.858,1.902,1.921,1.975,2.034,2.077,2.119,2.175,2.215,2.270,2.337,2.388,2.453,2.521,2.554,2.545,2.563,2.646,2.727,2.772,2.858,2.953,3.046,3.138,3.267,3.350,3.466,3.588,3.742,3.845,3.884,3.873,3.857,3.854,3.898,3.915,3.926,3.936,3.933,3.939,3.957,3.937,3.941,3.978,4.020,4.031,4.027,4.060,4.073,4.076,4.076,4.085,4.092,4.084,4.076,4.081,4.087,4.087,4.095,4.093,4.102,4.111,4.112,4.122,4.121,4.131,4.134,4.149,4.149,4.159,4.167,4.174,4.188,4.194,4.204,4.221,4.233,4.239,4.256,4.266,4.284,4.292,4.308,4.322,4.341,4.357,4.366,4.386,4.392,4.409,4.436,4.458,4.475,4.493,4.501,4.529,4.537,4.561,4.583,4.599,4.624,4.642,4.669,4.691,4.713,4.738,4.763,4.790,4.822,4.847,4.880,4.913,4.939,4.970,5.004,5.030,4.308,4.129,4.082,4.154,4.227,4.436,4.338,4.304,4.331,4.403,4.340,5.410,5.410,2.571,2.483,2.472,2.475,2.484,2.494,2.588},Reflectance=[181]{37.000,42.000,38.000,41.000,43.000,43.000,38.000,40.000,43.000,44.000,43.000,45.000,43.000,44.000,42.000,38.000,42.000,45.000,44.000,44.000,44.000,45.000,47.000,44.000,45.000,48.000,48.000,42.000,32.000,33.000,46.000,31.000,28.000,29.000,29.000,29.000,32.000,28.000,54.000,54.000,54.000,50.000,55.000,56.000,57.000,53.000,50.000,55.000,52.000,48.000,48.000,48.000,46.000,48.000,48.000,55.000,57.000,59.000,55.000,62.000,69.000,63.000,53.000,49.000,50.000,49.000,54.000,53.000,51.000,46.000,45.000,47.000,49.000,58.000,57.000,56.000,55.000,59.000,65.000,72.000,74.000,75.000,75.000,74.000,73.000,74.000,71.000,72.000,68.000,72.000,75.000,74.000,73.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,76.000,76.000,76.000,77.000,77.000,77.000,100.000,91.000,81.000,91.000,98.000,91.000,75.000,76.000,88.000,92.000,11.000,66.000,63.000,86.000,79.000,80.000,79.000,79.000,77.000,80.000}
-65.122 LMS_LASER_2D_RIGHT LMS2 ID=4161,time=1225719876.761724,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=250,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.472,18.285,15.558,12.834,10.762,9.620,8.780,8.060,7.300,6.710,6.225,5.767,5.389,5.111,4.707,4.456,4.230,3.983,3.810,3.622,3.400,3.287,3.157,3.020,2.891,2.793,2.705,2.583,2.511,2.429,2.354,2.271,2.200,2.139,2.093,2.004,1.961,1.901,1.850,1.794,1.744,1.701,1.679,1.643,1.614,1.587,1.554,1.504,1.476,1.420,1.405,1.393,1.375,1.328,1.311,1.295,1.276,1.242,1.234,1.223,1.189,1.178,1.154,1.138,1.105,1.098,1.082,1.074,1.073,1.064,1.063,1.055,1.060,1.065,1.068,1.076,1.082,1.079,1.078,1.040,1.038,1.028,1.030,1.059,1.040,1.041,1.036,1.023,1.020,1.006,0.995,0.985},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,26.000,28.000,111.000,109.000,91.000,63.000,57.000,53.000,54.000,61.000,66.000,66.000,67.000,69.000,72.000,71.000,73.000,74.000,74.000,75.000,73.000,77.000,78.000,78.000,78.000,80.000,80.000,79.000,80.000,79.000,80.000,79.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,75.000,75.000,79.000,79.000,78.000,78.000,74.000,75.000,77.000,75.000,76.000,76.000,66.000,65.000,75.000,69.000,67.000,70.000,69.000,67.000,66.000,63.000,66.000,67.000,69.000,69.000,72.000,72.000,71.000,69.000,69.000,68.000,63.000,57.000,55.000,51.000,38.000,35.000,37.000,27.000,27.000,27.000,27.000,47.000,57.000,57.000,52.000,50.000,45.000,42.000,49.000,52.000}
-65.122 LMS_LASER_2D_LEFT LMS1 ID=4289,time=1225719876.769532,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=30,Range=[181]{1.027,1.025,1.038,1.072,1.070,1.088,1.092,1.109,1.116,1.126,1.146,1.150,1.159,1.178,1.184,1.200,1.211,1.223,1.240,1.252,1.274,1.286,1.307,1.319,1.340,1.360,1.374,1.375,1.389,1.435,1.447,1.451,1.480,1.515,1.556,1.560,1.594,1.631,1.661,1.682,1.711,1.743,1.769,1.788,1.820,1.869,1.910,1.937,1.993,2.041,2.076,2.131,2.183,2.234,2.291,2.337,2.400,2.469,2.540,2.545,2.542,2.570,2.683,2.737,2.797,2.881,2.967,3.051,3.197,3.286,3.369,3.489,3.619,3.762,3.879,3.882,3.874,3.868,3.864,3.900,3.920,3.928,3.936,3.936,3.941,3.955,3.933,3.955,3.982,4.028,4.023,4.026,4.073,4.073,4.076,4.084,4.093,4.091,4.087,4.087,4.083,4.087,4.095,4.094,4.100,4.101,4.111,4.113,4.122,4.130,4.131,4.138,4.149,4.158,4.167,4.175,4.181,4.188,4.203,4.213,4.223,4.231,4.249,4.266,4.266,4.285,4.292,4.307,4.331,4.339,4.356,4.375,4.384,4.401,4.418,4.439,4.464,4.483,4.494,4.510,4.528,4.545,4.562,4.591,4.600,4.634,4.650,4.678,4.699,4.722,4.748,4.771,4.797,4.825,4.857,4.887,4.916,4.945,4.975,5.012,5.038,4.290,4.137,4.174,4.187,4.229,4.443,4.315,4.258,4.354,4.389,5.410,5.409,2.546,2.541,2.480,2.480,2.474,2.482,2.501,2.596},Reflectance=[181]{31.000,30.000,30.000,38.000,42.000,42.000,40.000,40.000,43.000,44.000,45.000,39.000,40.000,41.000,43.000,40.000,41.000,42.000,44.000,43.000,45.000,46.000,45.000,46.000,45.000,48.000,50.000,34.000,26.000,34.000,41.000,30.000,28.000,31.000,33.000,30.000,32.000,32.000,46.000,51.000,52.000,51.000,54.000,59.000,57.000,55.000,53.000,54.000,52.000,55.000,48.000,45.000,46.000,48.000,50.000,55.000,59.000,58.000,55.000,65.000,68.000,60.000,50.000,54.000,57.000,56.000,56.000,56.000,46.000,47.000,49.000,50.000,43.000,59.000,57.000,55.000,55.000,56.000,67.000,72.000,75.000,75.000,75.000,75.000,74.000,73.000,69.000,71.000,69.000,75.000,76.000,74.000,75.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,76.000,77.000,75.000,77.000,77.000,77.000,101.000,91.000,88.000,90.000,100.000,91.000,71.000,78.000,87.000,87.000,64.000,66.000,24.000,85.000,80.000,80.000,79.000,78.000,77.000,73.000}
-65.127 DESIRED_THRUST iJoystick 86.60237434
-65.127 DESIRED_RUDDER iJoystick 0
-65.131 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.9528,20.7424,-0.9350},Vel=[3x1]{-0.7660,-0.5654,-3.0769},Raw=[2x1]{23.5091,-0.9350},time=1225719876.77851867675781,Speed=0.95207499780964,Pitch=0.01346012240303,Roll=0.03589365974142,PitchDot=0.01121676866919,RollDot=0.00141331285232
-65.131 ODOMETRY_POSE iPlatform Pose=[3x1]{6.9528,20.7424,-0.9344},Vel=[3x1]{-0.7660,-0.5654,-3.0769},Raw=[2x1]{23.5091,-0.9350},time=1225719876.7785,Speed=0.9521,Pitch=-0.0209,Roll=0.0322,PitchDot=-0.0113,RollDot=-0.0007
-65.135 LMS_LASER_2D_RIGHT LMS2 ID=4162,time=1225719876.775068,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=251,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.731,15.083,12.506,10.464,9.440,8.640,7.883,7.191,6.613,6.118,5.671,5.335,5.040,4.663,4.411,4.177,3.940,3.782,3.594,3.383,3.250,3.112,2.996,2.861,2.767,2.655,2.565,2.495,2.415,2.328,2.244,2.200,2.139,2.086,2.020,1.935,1.868,1.824,1.779,1.748,1.716,1.676,1.643,1.615,1.580,1.540,1.502,1.446,1.396,1.404,1.385,1.347,1.315,1.307,1.287,1.260,1.227,1.216,1.207,1.189,1.171,1.163,1.139,1.122,1.106,1.090,1.075,1.073,1.065,1.050,1.048,1.052,1.054,1.064,1.078,1.082,1.067,1.041,1.034,1.038,1.041,1.067,1.052,1.029,1.034,1.033,1.020,0.967,1.008,0.987,0.980},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,52.000,107.000,105.000,89.000,61.000,55.000,54.000,56.000,62.000,66.000,67.000,67.000,69.000,71.000,71.000,73.000,75.000,74.000,74.000,74.000,77.000,79.000,79.000,80.000,80.000,81.000,79.000,80.000,80.000,80.000,77.000,80.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,79.000,77.000,78.000,79.000,79.000,79.000,75.000,74.000,76.000,74.000,72.000,71.000,66.000,73.000,74.000,71.000,70.000,73.000,70.000,68.000,66.000,64.000,65.000,69.000,68.000,70.000,71.000,73.000,70.000,71.000,74.000,70.000,63.000,56.000,53.000,45.000,38.000,31.000,28.000,27.000,27.000,28.000,47.000,63.000,69.000,62.000,50.000,37.000,27.000,43.000,52.000,53.000}
-65.135 LMS_LASER_2D_LEFT LMS1 ID=4290,time=1225719876.782868,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=31,Range=[181]{1.041,1.049,1.059,1.061,1.076,1.091,1.096,1.106,1.126,1.141,1.136,1.154,1.163,1.177,1.184,1.204,1.212,1.225,1.246,1.259,1.263,1.301,1.310,1.316,1.339,1.366,1.375,1.369,1.392,1.417,1.450,1.468,1.488,1.526,1.540,1.562,1.599,1.637,1.653,1.686,1.719,1.749,1.761,1.789,1.831,1.871,1.899,1.945,2.001,2.052,2.097,2.145,2.192,2.245,2.292,2.345,2.404,2.477,2.541,2.545,2.544,2.584,2.702,2.748,2.815,2.902,2.982,3.053,3.209,3.308,3.395,3.529,3.641,3.793,3.876,3.885,3.879,3.866,3.871,3.899,3.920,3.929,3.934,3.934,3.950,3.954,3.933,3.953,3.994,4.030,4.032,4.034,4.076,4.074,4.075,4.086,4.090,4.092,4.084,4.086,4.087,4.086,4.095,4.093,4.102,4.101,4.113,4.114,4.120,4.128,4.131,4.139,4.152,4.157,4.168,4.173,4.178,4.194,4.203,4.214,4.223,4.240,4.246,4.264,4.277,4.293,4.305,4.316,4.329,4.348,4.356,4.374,4.393,4.403,4.417,4.448,4.464,4.484,4.494,4.510,4.530,4.544,4.571,4.590,4.609,4.631,4.656,4.677,4.698,4.723,4.750,4.771,4.797,4.832,4.856,4.896,4.923,4.958,4.983,5.020,5.050,4.239,4.245,4.164,4.056,4.101,4.392,4.288,4.195,4.414,4.406,5.410,5.410,2.701,2.497,2.474,2.479,2.486,2.490,2.513,2.566},Reflectance=[181]{41.000,39.000,41.000,42.000,44.000,43.000,42.000,34.000,40.000,47.000,42.000,38.000,42.000,44.000,43.000,41.000,41.000,45.000,44.000,43.000,44.000,45.000,46.000,44.000,43.000,46.000,46.000,29.000,28.000,28.000,33.000,29.000,29.000,35.000,30.000,28.000,28.000,32.000,43.000,49.000,51.000,53.000,55.000,59.000,54.000,59.000,56.000,54.000,52.000,49.000,50.000,44.000,45.000,49.000,54.000,58.000,61.000,54.000,55.000,64.000,69.000,58.000,54.000,55.000,57.000,54.000,56.000,56.000,48.000,49.000,48.000,46.000,49.000,61.000,56.000,52.000,57.000,59.000,69.000,72.000,75.000,75.000,75.000,75.000,74.000,73.000,69.000,70.000,70.000,75.000,76.000,74.000,75.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,76.000,77.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,76.000,77.000,77.000,76.000,77.000,77.000,101.000,99.000,85.000,22.000,11.000,88.000,72.000,70.000,90.000,83.000,66.000,66.000,122.000,80.000,80.000,79.000,79.000,78.000,75.000,70.000}
-65.146 LMS_LASER_2D_RIGHT LMS2 ID=4163,time=1225719876.788410,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=252,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,17.167,14.551,11.942,10.262,9.301,8.465,7.756,7.098,6.503,6.025,5.612,5.121,4.839,4.604,4.366,4.128,3.919,3.699,3.561,3.369,3.226,3.094,2.963,2.844,2.749,2.654,2.557,2.485,2.415,2.321,2.229,2.194,2.128,2.061,2.010,1.932,1.866,1.824,1.777,1.747,1.698,1.680,1.642,1.604,1.576,1.524,1.470,1.429,1.385,1.394,1.369,1.342,1.333,1.312,1.279,1.251,1.234,1.215,1.207,1.190,1.165,1.148,1.133,1.121,1.105,1.095,1.079,1.063,1.049,1.050,1.048,1.045,1.058,1.065,1.079,1.054,1.047,1.041,1.038,1.031,1.074,1.051,1.038,1.041,1.034,1.030,1.020,0.969,1.004,0.983,0.974},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,72.000,109.000,107.000,80.000,59.000,56.000,54.000,57.000,63.000,67.000,66.000,71.000,74.000,70.000,71.000,74.000,74.000,77.000,78.000,76.000,78.000,79.000,79.000,79.000,80.000,81.000,80.000,80.000,80.000,78.000,78.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,76.000,77.000,79.000,79.000,78.000,78.000,75.000,75.000,76.000,71.000,70.000,73.000,74.000,76.000,76.000,72.000,71.000,70.000,68.000,69.000,68.000,68.000,69.000,72.000,66.000,67.000,64.000,66.000,68.000,72.000,73.000,69.000,64.000,54.000,50.000,35.000,30.000,27.000,28.000,27.000,27.000,41.000,58.000,69.000,61.000,54.000,49.000,37.000,27.000,37.000,51.000,50.000}
-65.151 DESIRED_THRUST iJoystick 86.60237434
-65.151 DESIRED_RUDDER iJoystick 0
-65.158 LMS_LASER_2D_RIGHT LMS2 ID=4164,time=1225719876.801751,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=253,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,-1.000,16.824,13.992,11.620,10.067,9.137,8.373,7.651,7.019,6.450,5.955,5.552,4.911,4.776,4.526,4.339,4.057,3.878,3.637,3.538,3.372,3.226,3.052,2.932,2.838,2.731,2.644,2.541,2.476,2.406,2.306,2.229,2.174,2.113,2.053,1.985,1.908,1.875,1.830,1.777,1.732,1.689,1.660,1.632,1.596,1.558,1.507,1.469,1.453,1.404,1.396,1.377,1.354,1.333,1.309,1.279,1.243,1.236,1.216,1.198,1.181,1.156,1.141,1.134,1.122,1.112,1.098,1.078,1.072,1.058,1.057,1.047,1.056,1.067,1.065,1.061,1.038,1.042,1.034,1.026,1.031,1.073,1.056,1.044,1.044,1.034,1.026,1.018,1.011,0.995,0.977,0.963},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,83.000,116.000,99.000,72.000,59.000,54.000,55.000,58.000,66.000,66.000,67.000,77.000,72.000,71.000,72.000,74.000,74.000,79.000,79.000,76.000,78.000,77.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,79.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,78.000,78.000,78.000,78.000,75.000,77.000,75.000,72.000,73.000,76.000,75.000,76.000,75.000,71.000,72.000,73.000,71.000,69.000,68.000,69.000,72.000,73.000,69.000,65.000,61.000,64.000,68.000,73.000,72.000,69.000,61.000,50.000,34.000,31.000,28.000,26.000,26.000,27.000,27.000,46.000,61.000,63.000,51.000,51.000,48.000,37.000,40.000,52.000,56.000,53.000}
-65.158 LMS_LASER_2D_LEFT LMS1 ID=4291,time=1225719876.796214,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=32,Range=[181]{1.050,1.053,1.044,1.055,1.079,1.094,1.099,1.117,1.117,1.139,1.145,1.159,1.169,1.189,1.192,1.205,1.219,1.237,1.248,1.263,1.278,1.290,1.300,1.320,1.344,1.367,1.374,1.372,1.404,1.428,1.456,1.465,1.496,1.535,1.533,1.577,1.596,1.648,1.671,1.700,1.736,1.750,1.772,1.796,1.849,1.873,1.900,1.963,1.999,2.048,2.114,2.152,2.188,2.256,2.304,2.360,2.433,2.492,2.527,2.554,2.539,2.608,2.703,2.759,2.845,2.925,2.992,3.092,3.228,3.329,3.425,3.552,3.683,3.798,3.887,3.877,3.879,3.862,3.876,3.911,3.929,3.937,3.934,3.933,3.950,3.950,3.930,3.964,4.004,4.032,4.031,4.042,4.078,4.075,4.077,4.086,4.092,4.093,4.086,4.085,4.087,4.087,4.097,4.103,4.102,4.104,4.112,4.113,4.121,4.131,4.140,4.140,4.149,4.156,4.167,4.173,4.185,4.193,4.211,4.214,4.231,4.238,4.255,4.265,4.284,4.293,4.301,4.327,4.338,4.356,4.364,4.374,4.393,4.401,4.426,4.448,4.475,4.485,4.500,4.518,4.530,4.551,4.579,4.588,4.617,4.640,4.664,4.686,4.707,4.734,4.755,4.779,4.814,4.842,4.872,4.906,4.936,4.964,4.999,5.034,5.058,5.082,4.255,4.182,5.190,4.544,4.350,4.229,4.243,4.376,4.446,5.415,4.551,2.625,2.483,2.472,2.477,2.483,2.486,2.519,2.398},Reflectance=[181]{41.000,38.000,29.000,30.000,35.000,41.000,43.000,36.000,41.000,46.000,42.000,40.000,44.000,45.000,40.000,42.000,41.000,45.000,42.000,40.000,47.000,44.000,42.000,42.000,40.000,47.000,43.000,26.000,31.000,31.000,32.000,29.000,28.000,44.000,30.000,26.000,28.000,35.000,38.000,38.000,48.000,54.000,55.000,58.000,54.000,60.000,57.000,54.000,55.000,47.000,45.000,51.000,43.000,46.000,55.000,61.000,58.000,61.000,66.000,63.000,67.000,57.000,47.000,48.000,51.000,50.000,56.000,55.000,48.000,46.000,49.000,44.000,51.000,59.000,57.000,52.000,58.000,63.000,70.000,73.000,75.000,75.000,75.000,74.000,74.000,72.000,69.000,69.000,70.000,76.000,75.000,74.000,76.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,79.000,78.000,78.000,78.000,78.000,79.000,77.000,77.000,77.000,78.000,77.000,76.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,75.000,76.000,76.000,75.000,77.000,77.000,93.000,92.000,75.000,96.000,82.000,72.000,78.000,92.000,83.000,68.000,90.000,108.000,79.000,80.000,79.000,79.000,77.000,74.000,74.000}
-65.167 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{6.9759,20.7595,-0.9337},Vel=[3x1]{-0.7759,-0.5741,-0.3846},Raw=[2x1]{23.5378,-0.9337},time=1225719876.81455564498901,Speed=0.96521713734996,Pitch=0.01346012240303,Roll=0.03813701347526,PitchDot=0.01346012240303,RollDot=0.00125627809095
-65.167 ODOMETRY_POSE iPlatform Pose=[3x1]{6.9759,20.7595,-0.9331},Vel=[3x1]{-0.7759,-0.5741,-0.3846},Raw=[2x1]{23.5378,-0.9337},time=1225719876.8146,Speed=0.9652,Pitch=-0.0226,Roll=0.0335,PitchDot=0.0120,RollDot=0.0062
-65.170 LMS_LASER_2D_LEFT LMS1 ID=4292,time=1225719876.809558,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=33,Range=[181]{1.048,1.055,1.046,1.072,1.084,1.092,1.104,1.110,1.131,1.139,1.149,1.158,1.169,1.186,1.196,1.209,1.225,1.232,1.247,1.262,1.279,1.295,1.310,1.319,1.354,1.365,1.374,1.386,1.427,1.436,1.451,1.471,1.499,1.545,1.537,1.572,1.620,1.643,1.668,1.704,1.740,1.741,1.773,1.811,1.858,1.898,1.934,1.973,2.006,2.068,2.114,2.160,2.205,2.267,2.312,2.358,2.435,2.509,2.537,2.554,2.555,2.627,2.708,2.778,2.863,2.930,3.021,3.122,3.249,3.342,3.440,3.571,3.672,3.839,3.893,3.879,3.864,3.854,3.877,3.912,3.929,3.933,3.934,3.940,3.958,3.945,3.933,3.970,4.015,4.031,4.031,4.058,4.071,4.074,4.084,4.084,4.091,4.090,4.086,4.085,4.088,4.093,4.096,4.102,4.101,4.111,4.111,4.121,4.121,4.130,4.140,4.150,4.149,4.156,4.166,4.177,4.194,4.203,4.204,4.223,4.230,4.246,4.248,4.265,4.282,4.292,4.308,4.325,4.339,4.356,4.364,4.381,4.392,4.410,4.435,4.457,4.475,4.493,4.500,4.521,4.538,4.551,4.579,4.599,4.617,4.642,4.666,4.690,4.706,4.734,4.757,4.789,4.816,4.851,4.873,4.913,4.937,4.963,4.997,5.036,5.066,4.516,4.160,4.198,5.202,4.471,4.291,4.199,4.359,4.281,4.613,5.418,4.438,2.602,2.486,2.472,2.483,2.481,2.494,2.404,2.299},Reflectance=[181]{40.000,35.000,28.000,32.000,37.000,41.000,44.000,40.000,46.000,46.000,46.000,43.000,44.000,41.000,42.000,40.000,46.000,42.000,41.000,43.000,43.000,45.000,49.000,44.000,45.000,50.000,43.000,24.000,36.000,40.000,30.000,27.000,28.000,44.000,30.000,28.000,33.000,42.000,44.000,40.000,53.000,58.000,56.000,57.000,50.000,52.000,53.000,55.000,54.000,45.000,43.000,51.000,47.000,46.000,55.000,60.000,59.000,64.000,69.000,61.000,67.000,57.000,53.000,49.000,48.000,48.000,50.000,52.000,50.000,49.000,48.000,45.000,53.000,54.000,56.000,53.000,58.000,65.000,71.000,73.000,75.000,77.000,75.000,74.000,74.000,71.000,67.000,68.000,71.000,75.000,75.000,75.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,79.000,80.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,77.000,76.000,76.000,75.000,75.000,76.000,77.000,95.000,81.000,96.000,77.000,96.000,77.000,71.000,92.000,79.000,89.000,69.000,85.000,104.000,79.000,80.000,79.000,78.000,77.000,78.000,76.000}
-65.175 DESIRED_THRUST iJoystick 86.60237434
-65.175 DESIRED_RUDDER iJoystick 0
-65.183 LMS_LASER_2D_LEFT LMS1 ID=4293,time=1225719876.822902,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=34,Range=[181]{1.053,1.062,1.063,1.070,1.088,1.092,1.101,1.113,1.126,1.140,1.150,1.162,1.180,1.191,1.197,1.209,1.225,1.236,1.259,1.258,1.284,1.301,1.320,1.334,1.353,1.370,1.377,1.381,1.427,1.450,1.469,1.472,1.500,1.555,1.567,1.584,1.607,1.660,1.682,1.703,1.734,1.751,1.779,1.827,1.867,1.909,1.928,1.988,2.032,2.076,2.118,2.160,2.221,2.276,2.329,2.376,2.443,2.518,2.537,2.562,2.563,2.664,2.707,2.794,2.872,2.946,3.040,3.160,3.274,3.363,3.468,3.585,3.740,3.878,3.887,3.881,3.862,3.860,3.889,3.915,3.929,3.938,3.933,3.933,3.956,3.935,3.939,3.975,4.017,4.032,4.030,4.055,4.070,4.082,4.085,4.084,4.092,4.091,4.085,4.086,4.087,4.085,4.095,4.102,4.101,4.110,4.113,4.119,4.129,4.130,4.140,4.149,4.149,4.167,4.166,4.178,4.187,4.203,4.214,4.225,4.239,4.249,4.256,4.275,4.281,4.293,4.316,4.325,4.346,4.354,4.374,4.392,4.401,4.417,4.437,4.455,4.476,4.493,4.503,4.520,4.539,4.562,4.583,4.600,4.626,4.644,4.667,4.687,4.715,4.742,4.766,4.787,4.823,4.849,4.882,4.919,4.936,4.962,5.004,5.035,5.062,4.271,4.214,5.167,5.200,4.386,4.241,4.218,4.386,4.286,5.382,5.421,4.394,2.569,2.477,2.477,2.478,2.483,2.416,2.317,2.302},Reflectance=[181]{38.000,38.000,38.000,38.000,38.000,40.000,44.000,44.000,47.000,46.000,47.000,42.000,46.000,46.000,42.000,43.000,46.000,40.000,46.000,42.000,46.000,46.000,46.000,45.000,44.000,48.000,43.000,27.000,34.000,49.000,35.000,28.000,29.000,46.000,36.000,28.000,28.000,36.000,38.000,41.000,51.000,54.000,59.000,52.000,54.000,53.000,54.000,50.000,51.000,52.000,55.000,51.000,43.000,45.000,55.000,60.000,59.000,64.000,67.000,61.000,63.000,53.000,56.000,52.000,52.000,47.000,47.000,45.000,49.000,50.000,48.000,47.000,45.000,49.000,53.000,54.000,61.000,68.000,71.000,74.000,75.000,76.000,74.000,72.000,74.000,68.000,65.000,67.000,71.000,76.000,75.000,75.000,76.000,77.000,78.000,78.000,77.000,77.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,75.000,75.000,75.000,75.000,76.000,76.000,89.000,90.000,76.000,76.000,92.000,73.000,71.000,92.000,78.000,69.000,69.000,80.000,92.000,79.000,79.000,77.000,76.000,79.000,76.000,77.000}
-65.170 LMS_LASER_2D_RIGHT LMS2 ID=4165,time=1225719876.815090,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=254,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-1.000,22.753,16.477,13.398,11.170,9.850,8.946,8.217,7.528,6.910,6.374,5.850,5.477,4.938,4.730,4.518,4.312,4.012,3.840,3.607,3.505,3.336,3.198,3.045,2.937,2.821,2.723,2.627,2.521,2.468,2.389,2.292,2.229,2.154,2.078,2.034,1.961,1.901,1.858,1.824,1.767,1.733,1.689,1.650,1.613,1.582,1.552,1.502,1.472,1.449,1.417,1.391,1.375,1.347,1.327,1.295,1.260,1.242,1.226,1.216,1.190,1.174,1.158,1.149,1.132,1.131,1.119,1.106,1.086,1.072,1.057,1.056,1.054,1.052,1.066,1.072,1.070,1.070,1.050,1.041,1.034,1.051,1.046,1.061,1.053,1.039,1.026,1.026,1.007,0.994,0.975,0.971,0.961},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,6.000,93.000,117.000,94.000,68.000,58.000,54.000,56.000,60.000,65.000,67.000,67.000,73.000,67.000,72.000,72.000,75.000,75.000,78.000,75.000,76.000,77.000,78.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,79.000,78.000,78.000,80.000,78.000,77.000,78.000,76.000,75.000,75.000,76.000,75.000,75.000,70.000,70.000,70.000,72.000,69.000,68.000,70.000,72.000,70.000,70.000,68.000,64.000,60.000,64.000,68.000,71.000,69.000,66.000,59.000,50.000,40.000,32.000,32.000,29.000,28.000,27.000,30.000,31.000,37.000,45.000,53.000,54.000,51.000,54.000,56.000,63.000,61.000,56.000}
-65.182 LMS_LASER_2D_RIGHT LMS2 ID=4166,time=1225719876.828429,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=255,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.602,21.445,15.902,13.118,10.965,9.712,8.819,8.096,7.379,6.715,6.279,5.803,5.433,5.025,4.688,4.491,4.273,3.981,3.825,3.610,3.465,3.323,3.193,3.038,2.906,2.795,2.715,2.605,2.498,2.454,2.362,2.283,2.228,2.145,2.095,2.027,1.953,1.901,1.850,1.806,1.750,1.725,1.679,1.643,1.607,1.580,1.541,1.483,1.462,1.431,1.431,1.399,1.369,1.334,1.314,1.294,1.268,1.251,1.226,1.200,1.182,1.167,1.159,1.141,1.138,1.128,1.111,1.098,1.086,1.063,1.056,1.054,1.053,1.057,1.073,1.074,1.072,1.071,1.045,1.074,1.073,1.071,1.063,1.051,1.033,1.018,1.014,1.013,1.004,0.989,0.974,0.963,0.960},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,16.000,14.000,110.000,112.000,92.000,65.000,57.000,53.000,56.000,63.000,64.000,67.000,68.000,71.000,69.000,71.000,72.000,74.000,76.000,77.000,77.000,78.000,78.000,78.000,80.000,80.000,80.000,80.000,78.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,79.000,78.000,76.000,78.000,76.000,76.000,75.000,73.000,74.000,72.000,67.000,68.000,70.000,72.000,72.000,70.000,71.000,73.000,71.000,67.000,63.000,64.000,61.000,64.000,68.000,69.000,67.000,65.000,57.000,46.000,46.000,38.000,34.000,29.000,36.000,32.000,45.000,49.000,51.000,57.000,63.000,61.000,60.000,60.000,57.000,62.000,61.000,56.000}
-65.183 LMS_LASER_2D_LEFT LMS1 ID=4294,time=1225719876.836234,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=35,Range=[181]{1.045,1.056,1.065,1.075,1.096,1.098,1.106,1.121,1.127,1.140,1.152,1.163,1.175,1.184,1.200,1.213,1.224,1.237,1.250,1.262,1.288,1.307,1.316,1.337,1.355,1.382,1.383,1.405,1.421,1.462,1.451,1.478,1.511,1.564,1.573,1.582,1.614,1.656,1.686,1.711,1.741,1.752,1.778,1.834,1.867,1.903,1.947,1.993,2.033,2.085,2.127,2.166,2.225,2.276,2.338,2.393,2.463,2.518,2.545,2.554,2.572,2.679,2.731,2.807,2.880,2.944,3.034,3.171,3.278,3.361,3.471,3.612,3.759,3.887,3.883,3.878,3.854,3.853,3.888,3.919,3.932,3.937,3.931,3.935,3.957,3.932,3.939,3.985,4.024,4.034,4.028,4.057,4.069,4.084,4.083,4.083,4.082,4.084,4.083,4.087,4.087,4.096,4.095,4.104,4.101,4.111,4.111,4.120,4.119,4.130,4.140,4.150,4.158,4.166,4.174,4.180,4.189,4.201,4.213,4.224,4.234,4.247,4.256,4.273,4.283,4.292,4.315,4.335,4.343,4.360,4.374,4.383,4.403,4.417,4.437,4.458,4.475,4.493,4.500,4.529,4.539,4.554,4.583,4.600,4.626,4.644,4.669,4.698,4.716,4.742,4.768,4.791,4.825,4.858,4.881,4.910,4.936,4.962,5.003,5.039,5.060,4.221,4.336,5.167,4.593,4.220,4.241,4.277,4.337,4.370,5.395,5.420,4.418,2.579,2.475,2.474,2.467,2.420,2.327,2.310,2.346},Reflectance=[181]{42.000,39.000,40.000,40.000,38.000,39.000,43.000,42.000,48.000,46.000,48.000,44.000,40.000,43.000,43.000,42.000,43.000,41.000,43.000,43.000,47.000,45.000,45.000,45.000,44.000,49.000,50.000,41.000,33.000,47.000,30.000,28.000,31.000,46.000,37.000,29.000,28.000,40.000,34.000,39.000,50.000,59.000,54.000,52.000,54.000,54.000,51.000,49.000,44.000,48.000,55.000,49.000,40.000,50.000,55.000,59.000,56.000,64.000,63.000,62.000,61.000,52.000,47.000,50.000,52.000,46.000,48.000,46.000,47.000,49.000,45.000,51.000,46.000,49.000,52.000,57.000,63.000,69.000,71.000,75.000,76.000,75.000,74.000,72.000,74.000,67.000,64.000,67.000,73.000,76.000,75.000,75.000,76.000,78.000,77.000,77.000,77.000,78.000,77.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,76.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,75.000,75.000,75.000,74.000,74.000,73.000,84.000,93.000,74.000,92.000,69.000,75.000,73.000,91.000,90.000,70.000,69.000,82.000,92.000,79.000,79.000,77.000,78.000,77.000,77.000,77.000}
-65.194 LMS_LASER_2D_RIGHT LMS2 ID=4167,time=1225719876.841765,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=0,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.743,18.347,15.562,12.954,10.879,9.676,8.782,8.034,7.310,6.705,6.215,5.767,5.407,5.058,4.689,4.465,4.238,3.981,3.780,3.599,3.461,3.323,3.176,2.983,2.915,2.793,2.682,2.586,2.493,2.442,2.355,2.273,2.211,2.147,2.096,2.027,1.927,1.884,1.841,1.788,1.750,1.725,1.680,1.643,1.598,1.567,1.520,1.496,1.470,1.437,1.420,1.388,1.360,1.335,1.305,1.286,1.261,1.252,1.225,1.209,1.181,1.158,1.150,1.133,1.132,1.120,1.119,1.094,1.079,1.063,1.056,1.054,1.052,1.049,1.064,1.067,1.062,1.082,1.078,1.081,1.069,1.062,1.059,1.042,1.033,1.031,1.015,1.001,0.996,0.989,0.976,0.964,0.974},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,30.000,20.000,115.000,109.000,92.000,65.000,58.000,53.000,55.000,64.000,64.000,67.000,68.000,69.000,71.000,71.000,72.000,74.000,76.000,75.000,78.000,78.000,78.000,80.000,80.000,80.000,81.000,80.000,80.000,80.000,78.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,79.000,78.000,77.000,78.000,78.000,76.000,76.000,74.000,72.000,74.000,71.000,69.000,72.000,71.000,71.000,71.000,68.000,72.000,72.000,72.000,69.000,65.000,63.000,64.000,66.000,69.000,70.000,66.000,63.000,57.000,46.000,34.000,35.000,38.000,42.000,49.000,44.000,52.000,51.000,54.000,62.000,61.000,61.000,63.000,60.000,57.000,59.000,58.000,54.000}
-65.199 DESIRED_THRUST iJoystick 86.60237434
-65.199 DESIRED_RUDDER iJoystick 0
-65.203 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{7.0065,20.7821,-0.9332},Vel=[3x1]{-0.7662,-0.5676,1.4103},Raw=[2x1]{23.5758,-0.9332},time=1225719876.85053277015686,Speed=0.95353523553635,Pitch=0.01570347613687,Roll=0.04262372094293,PitchDot=-0.00000000000000,RollDot=0.00094220856821
-65.203 ODOMETRY_POSE iPlatform Pose=[3x1]{7.0065,20.7821,-0.9324},Vel=[3x1]{-0.7662,-0.5676,1.4103},Raw=[2x1]{23.5758,-0.9332},time=1225719876.8505,Speed=0.9535,Pitch=-0.0249,Roll=0.0380,PitchDot=0.0009,RollDot=0.0002
-64.424 CAMERA_FILE_WRITE iCameraLadybug time=1225719876.072,Pan=0.00,Tilt=0.00,GrabType=ladybug,NumImages=5,File0=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719876.072-0.jpg,File1=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719876.072-1.jpg,File2=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719876.072-2.jpg,File3=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719876.072-3.jpg,File4=/home/mrg/MOOSData/LisaNewCollege/MOOSLog_3_11_2008_____13_43_32/Images/ladybug_1225719876.072-4.jpg
-64.831 RELAYBOX_STATUS iRelayBox LADYBUG is OFF,LMS1 is ON,LMS2 is ON,P10 is OFF,P11 is OFF,P12 is OFF,P13 is OFF,P14 is OFF,P15 is OFF,P16 is OFF,P5 is OFF,P6 is OFF,P7 is OFF,P8 is OFF,P9 is OFF,PANTILT is ON,
-65.194 LMS_LASER_2D_LEFT LMS1 ID=4295,time=1225719876.849563,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=36,Range=[181]{1.050,1.059,1.067,1.077,1.087,1.092,1.106,1.118,1.138,1.141,1.152,1.162,1.173,1.189,1.200,1.213,1.224,1.236,1.253,1.269,1.290,1.299,1.320,1.337,1.355,1.372,1.391,1.413,1.422,1.456,1.465,1.477,1.505,1.532,1.564,1.584,1.634,1.652,1.678,1.708,1.740,1.758,1.796,1.835,1.869,1.902,1.947,1.991,2.039,2.087,2.107,2.172,2.230,2.288,2.328,2.394,2.452,2.527,2.545,2.554,2.572,2.680,2.739,2.809,2.882,2.944,3.034,3.167,3.268,3.356,3.464,3.607,3.765,3.878,3.890,3.865,3.846,3.859,3.889,3.919,3.923,3.937,3.929,3.940,3.955,3.930,3.947,3.986,4.021,4.033,4.028,4.057,4.076,4.081,4.093,4.091,4.084,4.087,4.096,4.092,4.088,4.088,4.096,4.094,4.101,4.110,4.113,4.122,4.130,4.130,4.140,4.148,4.157,4.158,4.174,4.180,4.189,4.201,4.212,4.225,4.231,4.247,4.260,4.273,4.283,4.294,4.317,4.334,4.342,4.358,4.374,4.384,4.401,4.427,4.448,4.458,4.474,4.491,4.508,4.528,4.546,4.564,4.582,4.600,4.627,4.644,4.669,4.690,4.715,4.740,4.765,4.798,4.823,4.849,4.882,4.903,4.937,4.963,4.995,5.033,4.620,4.163,5.118,5.166,4.445,4.222,4.243,4.291,4.277,4.353,5.396,5.413,4.439,2.606,2.479,2.462,2.446,2.349,2.337,2.358,2.615},Reflectance=[181]{40.000,40.000,44.000,44.000,42.000,43.000,43.000,44.000,45.000,47.000,48.000,49.000,43.000,46.000,43.000,42.000,43.000,41.000,40.000,45.000,44.000,48.000,46.000,45.000,45.000,49.000,49.000,49.000,35.000,35.000,31.000,26.000,25.000,28.000,32.000,28.000,37.000,44.000,42.000,43.000,53.000,57.000,54.000,48.000,55.000,54.000,55.000,48.000,54.000,52.000,54.000,52.000,46.000,48.000,55.000,60.000,59.000,65.000,64.000,64.000,61.000,48.000,47.000,47.000,52.000,46.000,45.000,48.000,47.000,45.000,46.000,53.000,49.000,53.000,55.000,58.000,67.000,70.000,71.000,75.000,76.000,75.000,73.000,71.000,73.000,66.000,64.000,68.000,72.000,76.000,75.000,75.000,75.000,77.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,78.000,77.000,77.000,77.000,76.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,76.000,75.000,75.000,72.000,85.000,8.000,70.000,63.000,85.000,70.000,76.000,79.000,76.000,90.000,70.000,67.000,86.000,100.000,77.000,78.000,75.000,75.000,77.000,78.000,86.000}
-65.207 LMS_LASER_2D_RIGHT LMS2 ID=4168,time=1225719876.855102,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=1,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.702,18.308,15.501,12.865,10.788,9.594,8.701,8.025,7.294,6.714,6.207,5.749,5.380,5.041,4.647,4.447,4.221,3.949,3.780,3.609,3.457,3.313,3.176,3.024,2.898,2.793,2.678,2.584,2.496,2.430,2.350,2.274,2.209,2.142,2.096,2.025,1.935,1.875,1.839,1.786,1.760,1.717,1.676,1.649,1.605,1.568,1.532,1.492,1.464,1.437,1.418,1.386,1.358,1.327,1.306,1.269,1.252,1.242,1.225,1.213,1.195,1.173,1.150,1.134,1.124,1.115,1.104,1.080,1.072,1.055,1.055,1.053,1.058,1.055,1.063,1.057,1.062,1.057,1.063,1.070,1.071,1.060,1.043,1.038,1.033,1.030,1.014,1.007,0.998,0.990,0.983,0.973,0.976},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,19.000,29.000,113.000,107.000,91.000,64.000,58.000,53.000,55.000,63.000,65.000,67.000,68.000,69.000,72.000,71.000,73.000,75.000,76.000,76.000,77.000,77.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,81.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,76.000,75.000,72.000,71.000,75.000,72.000,70.000,72.000,70.000,70.000,65.000,63.000,68.000,72.000,74.000,72.000,69.000,66.000,68.000,68.000,69.000,68.000,66.000,57.000,52.000,34.000,30.000,30.000,30.000,31.000,37.000,49.000,51.000,55.000,60.000,62.000,60.000,61.000,57.000,61.000,54.000,54.000,54.000,51.000}
-65.207 LMS_LASER_2D_LEFT LMS1 ID=4296,time=1225719876.862892,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=37,Range=[181]{1.039,1.050,1.065,1.079,1.087,1.099,1.104,1.123,1.135,1.141,1.153,1.169,1.177,1.196,1.195,1.213,1.224,1.237,1.257,1.269,1.282,1.296,1.317,1.333,1.349,1.361,1.392,1.412,1.424,1.445,1.452,1.481,1.502,1.524,1.554,1.583,1.624,1.648,1.678,1.712,1.733,1.750,1.787,1.830,1.868,1.902,1.955,1.991,2.039,2.065,2.121,2.176,2.231,2.285,2.328,2.393,2.458,2.542,2.552,2.554,2.572,2.684,2.747,2.802,2.900,2.940,3.026,3.137,3.242,3.364,3.481,3.612,3.777,3.871,3.876,3.868,3.847,3.857,3.893,3.915,3.922,3.937,3.930,3.937,3.955,3.930,3.947,3.986,4.023,4.033,4.030,4.058,4.069,4.082,4.085,4.085,4.075,4.078,4.084,4.081,4.090,4.087,4.096,4.094,4.102,4.102,4.112,4.121,4.128,4.131,4.139,4.140,4.149,4.158,4.174,4.180,4.191,4.203,4.215,4.215,4.232,4.240,4.258,4.273,4.281,4.294,4.316,4.333,4.348,4.356,4.375,4.384,4.402,4.430,4.440,4.458,4.464,4.492,4.508,4.530,4.538,4.555,4.576,4.600,4.627,4.643,4.667,4.690,4.716,4.733,4.768,4.788,4.813,4.849,4.881,4.907,4.930,4.965,4.994,5.030,5.049,5.077,5.107,5.167,4.471,4.258,4.207,4.242,4.200,4.355,5.400,5.419,4.469,2.683,2.513,2.459,2.425,2.362,2.377,2.489,2.604},Reflectance=[181]{31.000,40.000,45.000,44.000,44.000,47.000,44.000,46.000,48.000,47.000,48.000,48.000,45.000,45.000,42.000,42.000,43.000,40.000,44.000,45.000,49.000,51.000,49.000,48.000,45.000,44.000,46.000,48.000,38.000,28.000,28.000,25.000,28.000,29.000,29.000,26.000,30.000,43.000,41.000,41.000,54.000,58.000,54.000,50.000,54.000,54.000,54.000,51.000,54.000,54.000,52.000,43.000,47.000,47.000,55.000,59.000,58.000,55.000,56.000,62.000,62.000,50.000,54.000,51.000,49.000,49.000,48.000,43.000,51.000,46.000,50.000,59.000,47.000,54.000,56.000,59.000,67.000,70.000,70.000,74.000,76.000,75.000,73.000,73.000,73.000,66.000,65.000,70.000,73.000,76.000,75.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,76.000,76.000,75.000,78.000,78.000,78.000,79.000,79.000,79.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,74.000,72.000,72.000,71.000,67.000,58.000,81.000,73.000,73.000,76.000,65.000,81.000,71.000,63.000,87.000,120.000,81.000,77.000,75.000,75.000,76.000,75.000,88.000}
-65.214 ICAMERALADYBUG_STATUS iCameraLadybug AppErrorFlag=false,Uptime=-1613.35,MOOSName=iCameraLadybug,Publishing=CAMERA_FILE_WRITE,ICAMERALADYBUG_STATUS,Subscribing=CAMERA_COMMAND,LOGGER_DIRECTORY,MARGE_ODOMETRY,NAV_POSE,SET_INTERPOSE_COMMAND,
-65.223 DESIRED_THRUST iJoystick 86.60237434
-65.223 DESIRED_RUDDER iJoystick 0
-65.230 LMS_LASER_2D_RIGHT LMS2 ID=4169,time=1225719876.868448,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=2,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.830,18.373,15.554,12.935,10.859,9.640,8.754,8.044,7.336,6.768,6.244,5.767,5.389,5.058,4.689,4.456,4.212,3.977,3.788,3.613,3.455,3.317,3.166,3.024,2.915,2.804,2.687,2.578,2.497,2.432,2.358,2.273,2.209,2.147,2.086,2.027,1.953,1.881,1.850,1.806,1.759,1.725,1.671,1.644,1.613,1.570,1.533,1.492,1.465,1.438,1.414,1.386,1.367,1.341,1.306,1.279,1.262,1.242,1.223,1.212,1.198,1.180,1.149,1.134,1.116,1.107,1.097,1.073,1.057,1.056,1.055,1.052,1.049,1.052,1.066,1.069,1.061,1.054,1.052,1.071,1.076,1.064,1.050,1.044,1.026,1.019,1.022,1.016,1.001,1.004,0.987,0.984,0.977},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,15.000,22.000,115.000,108.000,91.000,65.000,57.000,53.000,56.000,63.000,65.000,67.000,68.000,69.000,72.000,72.000,73.000,75.000,76.000,75.000,76.000,78.000,78.000,79.000,80.000,80.000,80.000,80.000,81.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,80.000,79.000,77.000,78.000,78.000,78.000,79.000,76.000,70.000,74.000,72.000,69.000,72.000,72.000,72.000,73.000,70.000,67.000,64.000,60.000,66.000,71.000,73.000,72.000,71.000,69.000,69.000,72.000,69.000,68.000,63.000,58.000,55.000,41.000,37.000,32.000,30.000,31.000,35.000,41.000,46.000,54.000,59.000,64.000,64.000,57.000,54.000,55.000,49.000,53.000,51.000,44.000}
-65.239 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{7.0299,20.7995,-0.9335},Vel=[3x1]{-0.7699,-0.5700,8.5897},Raw=[2x1]{23.6049,-0.9335},time=1225719876.88674354553223,Speed=0.95791594871645,Pitch=0.01346012240303,Roll=0.04486707467677,PitchDot=-0.02243353733839,RollDot=0.00004486707468
-65.239 ODOMETRY_POSE iPlatform Pose=[3x1]{7.0299,20.7995,-0.9327},Vel=[3x1]{-0.7699,-0.5700,2.3064},Raw=[2x1]{23.6049,-0.9335},time=1225719876.8867,Speed=0.9579,Pitch=-0.0280,Roll=0.0375,PitchDot=0.0151,RollDot=0.0166
-65.230 LMS_LASER_2D_LEFT LMS1 ID=4297,time=1225719876.876231,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=38,Range=[181]{1.029,1.061,1.070,1.067,1.088,1.095,1.097,1.119,1.133,1.141,1.151,1.166,1.180,1.183,1.202,1.209,1.231,1.236,1.251,1.273,1.286,1.305,1.321,1.338,1.355,1.371,1.395,1.405,1.416,1.433,1.450,1.496,1.508,1.524,1.574,1.575,1.612,1.656,1.687,1.706,1.733,1.750,1.796,1.834,1.859,1.913,1.944,1.997,2.039,2.081,2.121,2.172,2.230,2.277,2.328,2.385,2.440,2.531,2.573,2.559,2.572,2.675,2.720,2.789,2.886,2.948,3.001,3.128,3.225,3.363,3.458,3.627,3.719,3.849,3.878,3.862,3.844,3.856,3.883,3.914,3.930,3.929,3.933,3.936,3.951,3.929,3.939,3.978,4.016,4.032,4.022,4.050,4.071,4.073,4.075,4.076,4.076,4.067,4.076,4.079,4.087,4.092,4.096,4.096,4.102,4.102,4.112,4.113,4.120,4.129,4.140,4.140,4.148,4.158,4.167,4.174,4.183,4.196,4.205,4.214,4.230,4.236,4.248,4.263,4.281,4.294,4.310,4.333,4.340,4.359,4.372,4.383,4.401,4.421,4.439,4.447,4.463,4.483,4.498,4.528,4.538,4.555,4.575,4.599,4.617,4.644,4.660,4.690,4.707,4.733,4.758,4.780,4.812,4.849,4.875,4.900,4.923,4.956,4.988,5.022,5.053,5.075,5.106,5.169,5.214,4.338,4.183,4.188,4.191,4.287,5.392,5.410,4.409,4.258,2.590,2.468,2.449,2.420,2.454,2.481,2.574},Reflectance=[181]{28.000,42.000,42.000,44.000,46.000,45.000,43.000,48.000,47.000,47.000,43.000,46.000,45.000,39.000,40.000,39.000,46.000,43.000,45.000,49.000,46.000,47.000,46.000,46.000,46.000,49.000,48.000,49.000,33.000,26.000,27.000,47.000,34.000,29.000,35.000,29.000,29.000,48.000,45.000,44.000,54.000,54.000,54.000,52.000,54.000,55.000,49.000,46.000,46.000,46.000,42.000,48.000,46.000,51.000,55.000,60.000,62.000,51.000,53.000,59.000,61.000,54.000,54.000,53.000,47.000,48.000,49.000,47.000,51.000,46.000,48.000,58.000,55.000,48.000,57.000,62.000,66.000,69.000,70.000,74.000,76.000,75.000,74.000,75.000,75.000,66.000,65.000,70.000,74.000,76.000,75.000,76.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,76.000,76.000,76.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,72.000,73.000,70.000,65.000,58.000,58.000,80.000,71.000,68.000,65.000,71.000,66.000,64.000,88.000,75.000,102.000,77.000,76.000,75.000,75.000,76.000,87.000}
-65.242 LMS_LASER_2D_RIGHT LMS2 ID=4170,time=1225719876.881792,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=3,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,27.847,18.382,15.813,13.082,10.967,9.723,8.864,8.096,7.371,6.794,6.262,5.803,5.407,5.084,4.733,4.465,4.221,3.984,3.797,3.625,3.473,3.318,3.183,3.018,2.921,2.804,2.696,2.595,2.514,2.451,2.367,2.288,2.209,2.149,2.086,2.037,1.959,1.898,1.850,1.804,1.766,1.719,1.697,1.653,1.611,1.576,1.540,1.505,1.476,1.447,1.426,1.411,1.366,1.349,1.305,1.289,1.262,1.248,1.239,1.227,1.205,1.180,1.157,1.134,1.117,1.099,1.082,1.065,1.064,1.063,1.061,1.058,1.053,1.059,1.062,1.064,1.067,1.068,1.066,1.074,1.057,1.069,1.048,1.044,1.028,1.020,1.021,1.019,1.014,1.011,0.995,0.991,0.981},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,33.000,6.000,109.000,113.000,93.000,67.000,57.000,53.000,56.000,63.000,64.000,67.000,69.000,69.000,72.000,71.000,74.000,75.000,75.000,75.000,76.000,79.000,78.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,79.000,80.000,81.000,80.000,80.000,80.000,79.000,80.000,80.000,79.000,80.000,79.000,76.000,78.000,78.000,78.000,78.000,77.000,70.000,75.000,67.000,66.000,70.000,72.000,72.000,74.000,65.000,59.000,61.000,65.000,67.000,70.000,73.000,72.000,72.000,71.000,72.000,70.000,69.000,66.000,58.000,55.000,51.000,45.000,40.000,34.000,36.000,34.000,38.000,30.000,44.000,57.000,59.000,67.000,66.000,60.000,51.000,49.000,45.000,48.000,47.000,46.000}
-65.242 LMS_LASER_2D_LEFT LMS1 ID=4298,time=1225719876.889568,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=39,Range=[181]{1.030,1.049,1.071,1.073,1.092,1.096,1.107,1.113,1.133,1.136,1.152,1.166,1.175,1.186,1.198,1.214,1.223,1.228,1.251,1.269,1.278,1.298,1.304,1.333,1.346,1.360,1.389,1.397,1.418,1.421,1.457,1.468,1.494,1.538,1.564,1.581,1.605,1.649,1.668,1.696,1.717,1.742,1.793,1.827,1.867,1.895,1.940,1.983,2.025,2.070,2.117,2.160,2.216,2.269,2.319,2.370,2.440,2.507,2.564,2.545,2.563,2.659,2.717,2.780,2.871,2.944,2.983,3.095,3.199,3.332,3.428,3.581,3.706,3.851,3.879,3.862,3.850,3.851,3.876,3.913,3.923,3.930,3.933,3.923,3.950,3.931,3.930,3.972,4.011,4.023,4.024,4.050,4.061,4.064,4.078,4.078,4.068,4.078,4.076,4.081,4.079,4.087,4.087,4.095,4.096,4.104,4.104,4.112,4.122,4.122,4.131,4.138,4.148,4.158,4.166,4.174,4.187,4.196,4.205,4.215,4.223,4.237,4.247,4.263,4.278,4.291,4.294,4.318,4.334,4.347,4.360,4.382,4.381,4.407,4.429,4.451,4.463,4.482,4.492,4.519,4.537,4.545,4.564,4.590,4.607,4.642,4.662,4.688,4.706,4.734,4.750,4.782,4.805,4.849,4.866,4.885,4.925,4.948,4.984,5.017,5.048,5.080,5.106,5.152,5.203,5.235,4.237,4.228,4.253,4.277,5.383,5.405,4.278,4.235,2.674,2.525,2.462,2.452,2.458,2.471,2.497},Reflectance=[181]{30.000,43.000,46.000,45.000,47.000,46.000,46.000,45.000,47.000,48.000,48.000,46.000,47.000,40.000,50.000,45.000,50.000,44.000,46.000,47.000,45.000,48.000,47.000,48.000,45.000,43.000,49.000,52.000,45.000,27.000,28.000,57.000,53.000,35.000,38.000,31.000,30.000,34.000,41.000,42.000,54.000,54.000,53.000,49.000,50.000,55.000,48.000,45.000,37.000,38.000,39.000,45.000,48.000,47.000,55.000,62.000,61.000,56.000,53.000,63.000,62.000,51.000,53.000,50.000,48.000,50.000,49.000,48.000,50.000,45.000,45.000,49.000,57.000,52.000,57.000,62.000,68.000,70.000,70.000,74.000,76.000,76.000,74.000,71.000,72.000,67.000,66.000,69.000,72.000,76.000,76.000,76.000,76.000,77.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,78.000,77.000,77.000,75.000,77.000,78.000,77.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,76.000,77.000,76.000,74.000,71.000,65.000,58.000,58.000,59.000,77.000,72.000,77.000,71.000,61.000,67.000,78.000,74.000,112.000,85.000,78.000,77.000,77.000,78.000,75.000}
-65.247 DESIRED_THRUST iJoystick 86.60237434
-65.247 DESIRED_RUDDER iJoystick 0
-65.255 LMS_LASER_2D_RIGHT LMS2 ID=4171,time=1225719876.895136,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=4,Range=[181]{-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-1.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,-6.000,28.299,22.836,16.501,13.345,11.131,9.805,8.951,8.193,7.486,6.897,6.349,5.851,5.468,5.130,4.766,4.491,4.265,4.017,3.797,3.649,3.494,3.362,3.212,3.042,2.949,2.821,2.722,2.613,2.513,2.460,2.378,2.296,2.227,2.156,2.101,2.036,1.953,1.901,1.858,1.803,1.772,1.724,1.698,1.663,1.618,1.577,1.548,1.501,1.479,1.452,1.432,1.411,1.374,1.340,1.314,1.287,1.262,1.256,1.235,1.225,1.205,1.188,1.156,1.139,1.115,1.099,1.073,1.073,1.065,1.056,1.055,1.061,1.056,1.071,1.061,1.073,1.078,1.059,1.051,1.045,1.054,1.066,1.054,1.038,1.020,1.019,1.028,1.021,1.004,1.000,0.996,0.988,0.978},Reflectance=[181]{0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,0.000,12.000,1.000,92.000,119.000,96.000,68.000,57.000,54.000,57.000,62.000,65.000,67.000,68.000,69.000,72.000,71.000,73.000,74.000,75.000,75.000,77.000,78.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,80.000,80.000,80.000,80.000,80.000,80.000,80.000,79.000,78.000,79.000,79.000,77.000,77.000,78.000,77.000,76.000,78.000,75.000,76.000,68.000,65.000,71.000,72.000,71.000,73.000,63.000,53.000,60.000,65.000,66.000,69.000,67.000,69.000,71.000,71.000,70.000,71.000,70.000,68.000,59.000,53.000,45.000,31.000,40.000,37.000,31.000,30.000,29.000,30.000,38.000,52.000,60.000,66.000,65.000,59.000,52.000,53.000,51.000,42.000,40.000,49.000}
-65.255 LMS_LASER_2D_LEFT LMS1 ID=4299,time=1225719876.902905,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=40,Range=[181]{1.043,1.060,1.065,1.077,1.084,1.093,1.104,1.120,1.132,1.131,1.149,1.161,1.173,1.186,1.188,1.209,1.222,1.233,1.255,1.261,1.276,1.292,1.308,1.326,1.354,1.367,1.381,1.402,1.408,1.433,1.456,1.490,1.503,1.534,1.563,1.580,1.621,1.640,1.664,1.700,1.709,1.739,1.768,1.818,1.860,1.888,1.930,1.986,2.019,2.056,2.108,2.157,2.207,2.262,2.312,2.358,2.428,2.503,2.563,2.552,2.545,2.631,2.713,2.769,2.854,2.938,2.973,3.072,3.216,3.309,3.410,3.524,3.733,3.813,3.869,3.862,3.842,3.850,3.871,3.904,3.912,3.921,3.926,3.925,3.938,3.937,3.925,3.954,4.004,4.022,4.025,4.039,4.062,4.066,4.078,4.077,4.069,4.078,4.074,4.068,4.077,4.077,4.078,4.085,4.096,4.104,4.105,4.113,4.121,4.122,4.128,4.139,4.149,4.149,4.165,4.172,4.180,4.191,4.197,4.207,4.217,4.233,4.249,4.256,4.272,4.290,4.292,4.317,4.333,4.339,4.361,4.369,4.388,4.406,4.415,4.446,4.455,4.466,4.489,4.516,4.538,4.543,4.570,4.587,4.604,4.634,4.651,4.678,4.706,4.723,4.751,4.775,4.799,4.833,4.868,4.892,4.908,4.942,4.976,5.010,5.043,5.066,5.098,5.132,5.191,4.713,4.327,4.292,4.313,4.296,5.365,5.410,4.313,4.225,4.224,2.594,2.470,2.465,2.462,2.462,2.482},Reflectance=[181]{41.000,44.000,47.000,48.000,48.000,48.000,45.000,49.000,46.000,50.000,50.000,45.000,49.000,45.000,44.000,43.000,45.000,50.000,48.000,47.000,46.000,44.000,41.000,49.000,45.000,51.000,53.000,51.000,53.000,38.000,32.000,48.000,53.000,34.000,44.000,42.000,36.000,41.000,39.000,47.000,55.000,57.000,54.000,49.000,51.000,55.000,51.000,45.000,42.000,39.000,43.000,45.000,45.000,48.000,55.000,60.000,60.000,54.000,49.000,60.000,64.000,54.000,47.000,48.000,48.000,48.000,48.000,46.000,47.000,49.000,45.000,45.000,50.000,45.000,53.000,61.000,68.000,70.000,71.000,73.000,76.000,76.000,75.000,74.000,73.000,71.000,67.000,68.000,73.000,75.000,76.000,75.000,77.000,78.000,78.000,78.000,79.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,78.000,77.000,76.000,76.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,76.000,75.000,75.000,69.000,64.000,60.000,75.000,72.000,70.000,80.000,71.000,62.000,69.000,83.000,73.000,71.000,97.000,77.000,79.000,79.000,78.000,76.000}
-65.271 IJOYSTICK_STATUS iJoystick AppErrorFlag=false,Uptime=64.9221,MOOSName=iJoystick,Publishing=COLLISION_OK,DESIRED_RUDDER,DESIRED_THRUST,IJOYSTICK_STATUS,Subscribing=
-65.271 DESIRED_THRUST iJoystick 86.60237434
-65.271 DESIRED_RUDDER iJoystick 0
-65.275 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{7.0602,20.8219,-0.9361},Vel=[3x1]{-0.7526,-0.5541,10.6410},Raw=[2x1]{23.6427,-0.9361},time=1225719876.92258000373840,Speed=0.93455214508922,Pitch=0.01346012240303,Roll=0.04262372094293,PitchDot=-0.04262372094293,RollDot=-0.00089734149354
-65.275 ODOMETRY_POSE iPlatform Pose=[3x1]{7.0602,20.8219,-0.9353},Vel=[3x1]{-0.7526,-0.5541,-1.9250},Raw=[2x1]{23.6427,-0.9361},time=1225719876.9226,Speed=0.9346,Pitch=-0.0263,Roll=0.0361,PitchDot=0.0156,RollDot=-0.0397
-65.295 DESIRED_THRUST iJoystick 86.60237434
-65.295 DESIRED_RUDDER iJoystick 0
-65.311 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{7.0908,20.8443,-0.9404},Vel=[3x1]{-0.7478,-0.5457,12.5641},Raw=[2x1]{23.6806,-0.9404},time=1225719876.95858097076416,Speed=0.92579071872901,Pitch=0.01121676866919,Roll=0.04262372094293,PitchDot=-0.04486707467677,RollDot=-0.00080760734418
-65.311 ODOMETRY_POSE iPlatform Pose=[3x1]{7.0908,20.8443,-0.9397},Vel=[3x1]{-0.7478,-0.5457,-0.0023},Raw=[2x1]{23.6806,-0.9404},time=1225719876.9586,Speed=0.9258,Pitch=-0.0278,Roll=0.0342,PitchDot=-0.0449,RollDot=-0.0009
-65.319 DESIRED_THRUST iJoystick 86.60237434
-65.319 DESIRED_RUDDER iJoystick 0
-65.343 DESIRED_THRUST iJoystick 86.60237434
-65.343 DESIRED_RUDDER iJoystick 0
-65.348 PLOGGER_STATUS pLogger AppErrorFlag=false,Uptime=65.3474,MOOSName=pLogger,Publishing=LOGGER_DIRECTORY,PLOGGER_STATUS,Subscribing=ANTLER_STATUS,CAMERA_COMMAND,CAMERA_FILE_WRITE,COLLISION_OK,DB_CLIENTS,DB_TIME,DB_UPTIME,DESIRED_ELEVATOR,DESIRED_RUDDER,DESIRED_THRUST,EKF_ENABLE,GPS,ICAMERABUMBLEBEE_STATUS,ICAMERALADYBUG_STATUS,ICAMERA_STATUS,IGPS_STATUS,IJOYSTICK_STATUS,IPLATFORM_CMD,IPLATFORM_STATUS,IRELAYBOX_STATUS,LASER_LAG,LMS1_CMD,LMS1_STATUS,LMS2_CMD,LMS2_STATUS,LMS_LASER_2D_LEFT,LMS_LASER_2D_RIGHT,LOCAL_LASER_LAG,LOGGER_DIRECTORY,LOGGER_RESTART,LSQ_ENABLE,MARGE_ODOMETRY,MISSION_FILE,MOOS_DEBUG,MOOS_MANUAL_OVERIDE,MOOS_SYSTEM,NAV_POSE,NAV_SUMMARY,NAV_SUMMARY_REQUEST,ODOMETRY_POSE,ODOM_UNITS_PER_METER,ODOM_UNITS_PER_RADIAN,PLOGGER_CMD,PLOGGER_STATUS,PLOGSTEREO_CMD,PLOGSTEREO_STATUS,PNAV_STATUS,QUERY_ODOM_CALIBRATION,RELAYBOX_CMD,RELAYBOX_STATUS,RESET_ACTUATION,RESTART_NAV,SET_INTERPOSE_COMMAND,TOP_DOWN_CAL_CONTROL,UWATCHDOG_STATUS,VEHICLE_GEOMETRY,
-65.348 RAW_ODOMETRY_POSE iPlatform Pose=[3x1]{7.1138,20.8610,-0.9445},Vel=[3x1]{-0.7501,-0.5426,8.0769},Raw=[2x1]{23.7091,-0.9445},time=1225719876.99506878852844,Speed=0.92579071872901,Pitch=0.00897341493535,Roll=0.03813701347526,PitchDot=-0.03813701347526,RollDot=-0.00170494883772
-65.348 ODOMETRY_POSE iPlatform Pose=[3x1]{7.1138,20.8610,-0.9439},Vel=[3x1]{-0.7501,-0.5426,1.7936},Raw=[2x1]{23.7091,-0.9445},time=1225719876.9951,Speed=0.9258,Pitch=-0.0256,Roll=0.0296,PitchDot=0.0068,RollDot=0.0376
-65.266 LMS_LASER_2D_LEFT LMS1 ID=4300,time=1225719876.916239,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=41,Range=[181]{1.049,1.051,1.066,1.066,1.083,1.097,1.099,1.109,1.127,1.132,1.144,1.164,1.169,1.188,1.185,1.207,1.213,1.234,1.249,1.259,1.275,1.283,1.312,1.326,1.344,1.355,1.372,1.387,1.409,1.435,1.469,1.485,1.488,1.530,1.556,1.591,1.600,1.635,1.658,1.696,1.703,1.733,1.768,1.811,1.846,1.892,1.925,1.976,2.003,2.053,2.100,2.142,2.187,2.242,2.303,2.360,2.405,2.477,2.553,2.554,2.534,2.606,2.709,2.757,2.822,2.913,2.962,3.052,3.211,3.308,3.381,3.494,3.692,3.797,3.868,3.854,3.847,3.844,3.857,3.893,3.911,3.920,3.920,3.925,3.942,3.942,3.913,3.946,3.997,4.018,4.014,4.024,4.062,4.065,4.069,4.067,4.069,4.068,4.069,4.072,4.068,4.079,4.078,4.086,4.096,4.094,4.103,4.104,4.113,4.120,4.122,4.138,4.138,4.147,4.155,4.163,4.179,4.189,4.195,4.206,4.217,4.225,4.242,4.251,4.267,4.284,4.295,4.310,4.326,4.335,4.352,4.370,4.387,4.395,4.417,4.436,4.455,4.474,4.482,4.507,4.529,4.543,4.562,4.586,4.595,4.630,4.642,4.669,4.706,4.716,4.740,4.766,4.790,4.823,4.849,4.885,4.900,4.932,4.967,4.992,5.026,5.059,5.091,5.123,3.240,3.466,4.287,4.249,4.392,4.390,5.355,4.083,4.258,4.253,4.198,2.534,2.550,2.466,2.464,2.466,2.470},Reflectance=[181]{43.000,45.000,47.000,43.000,47.000,46.000,50.000,47.000,48.000,46.000,48.000,46.000,48.000,45.000,48.000,46.000,49.000,47.000,50.000,46.000,44.000,49.000,46.000,49.000,49.000,50.000,53.000,52.000,54.000,45.000,35.000,32.000,30.000,39.000,43.000,46.000,32.000,54.000,49.000,45.000,56.000,58.000,54.000,53.000,49.000,49.000,52.000,49.000,42.000,49.000,40.000,45.000,43.000,51.000,51.000,58.000,63.000,58.000,52.000,61.000,66.000,56.000,49.000,47.000,49.000,48.000,47.000,52.000,49.000,49.000,50.000,43.000,51.000,47.000,56.000,62.000,69.000,71.000,72.000,72.000,75.000,75.000,75.000,74.000,74.000,72.000,66.000,68.000,71.000,74.000,76.000,76.000,77.000,77.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,77.000,76.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,76.000,76.000,75.000,72.000,69.000,19.000,113.000,65.000,68.000,88.000,85.000,62.000,5.000,82.000,79.000,78.000,24.000,91.000,79.000,80.000,79.000,77.000}
-65.278 LMS_LASER_2D_LEFT LMS1 ID=4301,time=1225719876.929572,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=42,Range=[181]{1.038,1.053,1.062,1.073,1.076,1.093,1.101,1.115,1.118,1.135,1.137,1.156,1.166,1.182,1.192,1.200,1.214,1.226,1.243,1.262,1.278,1.281,1.303,1.318,1.342,1.360,1.364,1.382,1.409,1.430,1.459,1.484,1.505,1.528,1.553,1.583,1.600,1.620,1.635,1.686,1.698,1.733,1.759,1.792,1.815,1.881,1.920,1.966,2.008,2.049,2.089,2.140,2.180,2.236,2.304,2.345,2.405,2.480,2.536,2.535,2.540,2.588,2.697,2.757,2.802,2.898,2.963,3.027,3.197,3.290,3.359,3.471,3.639,3.769,3.856,3.838,3.845,3.839,3.854,3.883,3.910,3.912,3.919,3.925,3.932,3.943,3.922,3.938,3.992,4.015,4.014,4.022,4.062,4.065,4.067,4.069,4.068,4.069,4.072,4.061,4.069,4.077,4.079,4.077,4.086,4.095,4.095,4.104,4.112,4.110,4.118,4.126,4.135,4.145,4.155,4.162,4.170,4.185,4.193,4.198,4.207,4.226,4.232,4.252,4.257,4.274,4.293,4.300,4.321,4.336,4.345,4.363,4.380,4.388,4.408,4.428,4.445,4.461,4.474,4.498,4.519,4.533,4.550,4.578,4.594,4.622,4.637,4.664,4.698,4.725,4.739,4.766,4.789,4.813,4.848,4.872,4.900,4.929,4.956,4.989,5.022,5.053,5.082,5.123,3.192,3.332,3.385,4.273,5.294,5.328,5.337,5.401,4.004,4.188,4.106,4.120,2.630,2.481,2.470,2.468,2.465},Reflectance=[181]{43.000,45.000,46.000,46.000,45.000,48.000,48.000,46.000,44.000,48.000,49.000,46.000,46.000,46.000,47.000,47.000,44.000,47.000,51.000,48.000,47.000,48.000,46.000,49.000,48.000,48.000,53.000,53.000,54.000,48.000,46.000,37.000,40.000,42.000,49.000,54.000,45.000,59.000,54.000,53.000,54.000,54.000,54.000,56.000,59.000,49.000,50.000,45.000,48.000,47.000,50.000,49.000,44.000,45.000,51.000,58.000,61.000,55.000,57.000,66.000,68.000,56.000,48.000,47.000,48.000,52.000,51.000,49.000,50.000,49.000,48.000,44.000,48.000,51.000,58.000,67.000,69.000,69.000,71.000,72.000,75.000,76.000,75.000,74.000,71.000,70.000,66.000,66.000,72.000,73.000,76.000,75.000,77.000,77.000,78.000,79.000,78.000,78.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,78.000,77.000,78.000,77.000,77.000,77.000,76.000,77.000,76.000,76.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,75.000,75.000,73.000,72.000,71.000,39.000,91.000,95.000,72.000,67.000,65.000,66.000,63.000,27.000,81.000,69.000,70.000,105.000,78.000,79.000,79.000,78.000}
-65.290 LMS_LASER_2D_LEFT LMS1 ID=4302,time=1225719876.942904,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=43,Range=[181]{1.034,1.053,1.059,1.071,1.075,1.083,1.095,1.103,1.115,1.121,1.144,1.142,1.156,1.175,1.187,1.200,1.213,1.233,1.239,1.255,1.272,1.288,1.287,1.316,1.332,1.347,1.365,1.392,1.407,1.426,1.452,1.469,1.499,1.518,1.546,1.565,1.602,1.621,1.649,1.685,1.698,1.712,1.746,1.781,1.822,1.878,1.912,1.947,1.986,2.032,2.073,2.106,2.161,2.228,2.285,2.333,2.397,2.462,2.522,2.535,2.538,2.578,2.701,2.744,2.792,2.868,2.958,2.997,3.172,3.275,3.344,3.444,3.593,3.739,3.837,3.851,3.843,3.835,3.852,3.887,3.903,3.912,3.920,3.915,3.919,3.939,3.913,3.930,3.978,4.006,4.013,4.012,4.042,4.056,4.066,4.067,4.059,4.060,4.067,4.061,4.069,4.068,4.069,4.078,4.077,4.087,4.087,4.097,4.104,4.111,4.118,4.128,4.126,4.137,4.148,4.158,4.160,4.178,4.187,4.197,4.206,4.215,4.233,4.242,4.250,4.265,4.283,4.304,4.313,4.328,4.336,4.355,4.370,4.388,4.396,4.417,4.439,4.457,4.466,4.482,4.509,4.526,4.543,4.562,4.590,4.606,4.630,4.656,4.685,4.715,4.730,4.755,4.781,4.803,4.838,4.864,4.892,4.921,4.947,4.992,5.010,5.043,5.070,5.112,3.129,3.270,3.349,3.250,5.292,5.311,5.331,4.059,4.158,4.078,4.042,4.120,4.157,2.567,2.474,2.466,2.468},Reflectance=[181]{40.000,44.000,44.000,45.000,43.000,47.000,49.000,49.000,46.000,44.000,45.000,47.000,50.000,47.000,49.000,47.000,49.000,46.000,49.000,48.000,48.000,47.000,43.000,48.000,51.000,50.000,50.000,54.000,53.000,38.000,38.000,46.000,48.000,49.000,53.000,54.000,48.000,52.000,52.000,48.000,54.000,60.000,56.000,55.000,54.000,55.000,51.000,43.000,43.000,40.000,43.000,57.000,55.000,45.000,54.000,57.000,58.000,59.000,55.000,65.000,67.000,59.000,50.000,49.000,47.000,50.000,49.000,48.000,46.000,50.000,49.000,46.000,47.000,45.000,62.000,75.000,71.000,68.000,73.000,73.000,75.000,76.000,75.000,74.000,72.000,73.000,65.000,65.000,70.000,73.000,75.000,75.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,79.000,78.000,77.000,78.000,77.000,78.000,78.000,79.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,79.000,78.000,79.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,76.000,76.000,77.000,78.000,77.000,77.000,78.000,77.000,76.000,77.000,77.000,76.000,76.000,76.000,74.000,71.000,71.000,71.000,36.000,94.000,94.000,33.000,64.000,67.000,67.000,30.000,92.000,80.000,71.000,70.000,64.000,91.000,79.000,80.000,79.000}
-65.303 LMS_LASER_2D_LEFT LMS1 ID=4303,time=1225719876.956236,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=44,Range=[181]{1.033,1.042,1.056,1.058,1.077,1.083,1.090,1.099,1.119,1.124,1.139,1.144,1.152,1.176,1.180,1.195,1.214,1.225,1.224,1.254,1.269,1.275,1.302,1.303,1.328,1.343,1.361,1.389,1.401,1.415,1.432,1.470,1.486,1.512,1.543,1.566,1.595,1.619,1.654,1.676,1.696,1.708,1.732,1.785,1.825,1.863,1.895,1.945,1.984,2.023,2.070,2.104,2.143,2.213,2.270,2.314,2.385,2.448,2.521,2.541,2.535,2.554,2.680,2.727,2.780,2.864,2.937,2.989,3.116,3.275,3.337,3.434,3.579,3.694,3.837,3.843,3.839,3.838,3.838,3.868,3.903,3.904,3.910,3.915,3.911,3.933,3.911,3.922,3.954,3.993,4.013,4.006,4.033,4.047,4.054,4.065,4.059,4.060,4.060,4.060,4.065,4.069,4.068,4.069,4.078,4.078,4.086,4.095,4.105,4.111,4.111,4.120,4.121,4.129,4.146,4.153,4.162,4.170,4.177,4.190,4.197,4.208,4.226,4.235,4.242,4.258,4.274,4.283,4.301,4.319,4.336,4.344,4.362,4.379,4.390,4.410,4.430,4.446,4.457,4.483,4.502,4.518,4.533,4.552,4.578,4.595,4.622,4.640,4.675,4.696,4.712,4.737,4.764,4.794,4.822,4.856,4.883,4.912,4.936,4.973,5.003,5.034,5.056,5.087,5.124,3.143,3.232,3.283,5.283,5.310,5.331,4.118,4.081,4.061,4.045,4.175,4.097,2.527,2.473,2.460,2.457},Reflectance=[181]{44.000,44.000,40.000,43.000,48.000,47.000,40.000,47.000,45.000,46.000,49.000,48.000,52.000,51.000,49.000,48.000,49.000,46.000,43.000,45.000,47.000,49.000,49.000,54.000,46.000,44.000,48.000,52.000,54.000,42.000,32.000,47.000,54.000,50.000,52.000,54.000,52.000,38.000,37.000,49.000,53.000,54.000,54.000,53.000,52.000,52.000,55.000,46.000,44.000,43.000,37.000,53.000,55.000,47.000,48.000,55.000,56.000,62.000,55.000,59.000,69.000,62.000,56.000,53.000,49.000,56.000,55.000,48.000,50.000,57.000,50.000,46.000,49.000,52.000,64.000,75.000,74.000,74.000,71.000,73.000,75.000,76.000,75.000,74.000,73.000,74.000,68.000,65.000,68.000,72.000,75.000,76.000,76.000,77.000,77.000,77.000,78.000,78.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,77.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,76.000,74.000,73.000,72.000,68.000,67.000,43.000,58.000,57.000,64.000,66.000,67.000,81.000,83.000,80.000,79.000,76.000,64.000,42.000,76.000,79.000,78.000}
-65.314 LMS_LASER_2D_LEFT LMS1 ID=4304,time=1225719876.969565,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=45,Range=[181]{1.033,1.054,1.059,1.065,1.073,1.082,1.088,1.093,1.112,1.119,1.125,1.138,1.152,1.166,1.175,1.186,1.203,1.220,1.233,1.244,1.266,1.273,1.285,1.304,1.322,1.340,1.356,1.379,1.391,1.413,1.417,1.461,1.478,1.510,1.521,1.548,1.588,1.613,1.636,1.659,1.694,1.706,1.725,1.775,1.813,1.847,1.876,1.931,1.974,2.012,2.043,2.096,2.131,2.189,2.239,2.294,2.366,2.444,2.496,2.549,2.527,2.535,2.627,2.710,2.769,2.832,2.898,2.985,3.092,3.199,3.330,3.438,3.525,3.662,3.802,3.837,3.838,3.834,3.833,3.860,3.887,3.896,3.911,3.908,3.904,3.925,3.914,3.904,3.941,3.982,4.008,4.000,4.013,4.057,4.055,4.058,4.051,4.050,4.060,4.063,4.052,4.060,4.069,4.067,4.070,4.075,4.086,4.086,4.096,4.105,4.103,4.112,4.121,4.129,4.138,4.148,4.158,4.164,4.172,4.188,4.189,4.207,4.208,4.225,4.243,4.252,4.267,4.276,4.290,4.309,4.327,4.336,4.352,4.370,4.387,4.398,4.419,4.438,4.457,4.474,4.491,4.510,4.527,4.542,4.570,4.588,4.612,4.631,4.660,4.681,4.703,4.729,4.754,4.778,4.805,4.831,4.866,4.897,4.927,4.963,4.989,5.017,5.039,5.074,3.364,5.158,5.211,3.266,3.268,3.195,5.328,4.184,3.962,3.947,3.970,4.071,4.076,2.429,2.423,2.435,2.439},Reflectance=[181]{41.000,45.000,45.000,47.000,46.000,47.000,45.000,48.000,45.000,48.000,47.000,49.000,48.000,50.000,50.000,48.000,48.000,48.000,50.000,47.000,46.000,49.000,50.000,47.000,51.000,51.000,50.000,52.000,53.000,49.000,30.000,45.000,54.000,53.000,54.000,54.000,49.000,52.000,45.000,40.000,48.000,58.000,55.000,53.000,54.000,49.000,54.000,48.000,45.000,46.000,42.000,53.000,50.000,36.000,43.000,55.000,56.000,55.000,55.000,55.000,66.000,65.000,57.000,50.000,48.000,53.000,59.000,50.000,55.000,54.000,55.000,47.000,49.000,57.000,57.000,66.000,71.000,75.000,72.000,73.000,76.000,76.000,75.000,75.000,73.000,74.000,69.000,66.000,67.000,71.000,74.000,77.000,75.000,78.000,77.000,78.000,78.000,78.000,79.000,79.000,79.000,79.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,76.000,77.000,77.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,75.000,75.000,75.000,73.000,69.000,70.000,7.000,66.000,61.000,53.000,27.000,17.000,64.000,92.000,73.000,71.000,68.000,74.000,60.000,31.000,74.000,77.000,78.000}
-65.338 LMS_LASER_2D_LEFT LMS1 ID=4305,time=1225719876.982905,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=46,Range=[181]{1.028,1.033,1.042,1.059,1.071,1.079,1.087,1.093,1.105,1.122,1.127,1.135,1.142,1.162,1.178,1.185,1.195,1.206,1.226,1.238,1.256,1.272,1.280,1.300,1.318,1.320,1.342,1.367,1.383,1.404,1.428,1.447,1.474,1.495,1.522,1.552,1.582,1.597,1.620,1.661,1.684,1.708,1.712,1.750,1.790,1.829,1.875,1.912,1.956,1.995,2.038,2.079,2.101,2.170,2.229,2.285,2.328,2.410,2.482,2.540,2.527,2.525,2.572,2.698,2.746,2.799,2.876,2.960,3.048,3.170,3.308,3.413,3.502,3.622,3.712,3.848,3.828,3.837,3.832,3.838,3.873,3.889,3.904,3.908,3.903,3.906,3.921,3.896,3.922,3.964,3.996,4.006,3.996,4.049,4.058,4.049,4.050,4.042,4.051,4.050,4.049,4.051,4.059,4.061,4.067,4.067,4.076,4.076,4.087,4.096,4.104,4.111,4.122,4.122,4.129,4.146,4.157,4.165,4.171,4.173,4.181,4.197,4.206,4.224,4.232,4.241,4.257,4.266,4.280,4.298,4.316,4.335,4.345,4.361,4.377,4.389,4.412,4.429,4.445,4.455,4.482,4.501,4.519,4.534,4.551,4.577,4.597,4.624,4.641,4.667,4.687,4.720,4.742,4.767,4.793,4.821,4.848,4.890,4.909,4.938,4.971,5.002,5.025,3.308,3.397,3.426,3.276,3.256,3.253,3.210,3.183,5.328,3.521,3.934,3.954,4.042,4.007,3.894,2.527,2.488,2.417},Reflectance=[181]{38.000,41.000,44.000,48.000,45.000,46.000,49.000,48.000,46.000,46.000,48.000,48.000,43.000,49.000,48.000,48.000,41.000,49.000,51.000,49.000,49.000,48.000,48.000,45.000,53.000,54.000,52.000,51.000,54.000,48.000,40.000,52.000,52.000,54.000,54.000,48.000,50.000,53.000,52.000,45.000,48.000,54.000,60.000,54.000,52.000,50.000,49.000,54.000,47.000,46.000,38.000,53.000,55.000,34.000,37.000,47.000,55.000,56.000,49.000,51.000,64.000,68.000,61.000,49.000,46.000,46.000,54.000,50.000,54.000,53.000,49.000,52.000,51.000,56.000,55.000,58.000,66.000,74.000,72.000,71.000,74.000,76.000,76.000,75.000,73.000,72.000,71.000,66.000,66.000,69.000,73.000,76.000,75.000,75.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,79.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,77.000,76.000,77.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,76.000,77.000,77.000,77.000,77.000,78.000,77.000,76.000,76.000,76.000,77.000,77.000,77.000,75.000,73.000,75.000,74.000,70.000,35.000,99.000,108.000,27.000,28.000,56.000,30.000,27.000,66.000,92.000,75.000,73.000,76.000,65.000,34.000,100.000,87.000,75.000}
-65.351 LMS_LASER_2D_LEFT LMS1 ID=4306,time=1225719876.996244,angRes=0.50,offset=0.00,minAngle=45.00,maxAngle=135.00,scanCount=47,Range=[181]{1.005,1.040,1.038,1.053,1.058,1.063,1.080,1.095,1.104,1.110,1.115,1.129,1.137,1.159,1.174,1.188,1.194,1.211,1.216,1.235,1.243,1.267,1.282,1.286,1.303,1.319,1.341,1.362,1.374,1.393,1.423,1.445,1.460,1.486,1.505,1.541,1.567,1.593,1.609,1.638,1.663,1.689,1.702,1.742,1.781,1.820,1.857,1.897,1.931,1.976,2.025,2.064,2.108,2.149,2.200,2.263,2.325,2.383,2.463,2.527,2.535,2.519,2.545,2.680,2.725,2.776,2.842,2.924,3.020,3.107,3.270,3.371,3.487,3.591,3.652,3.821,3.828,3.834,3.826,3.828,3.860,3.887,3.895,3.902,3.906,3.906,3.921,3.899,3.904,3.944,3.985,4.004,3.991,4.031,4.047,4.048,4.041,4.042,4.042,4.050,4.052,4.052,4.049,4.058,4.057,4.066,4.068,4.075,4.085,4.086,4.103,4.113,4.112,4.119,4.130,4.139,4.149,4.164,4.165,4.173,4.181,4.191,4.198,4.207,4.226,4.243,4.249,4.267,4.276,4.289,4.310,4.320,4.337,4.353,4.374,4.379,4.398,4.420,4.444,4.455,4.473,4.491,4.511,4.527,4.552,4.571,4.588,4.605,4.631,4.661,4.681,4.703,4.735,4.761,4.782,4.816,4.839,4.880,4.901,4.926,4.953,4.991,5.015,3.461,3.293,3.280,3.349,3.349,3.319,3.235,3.181,3.167,3.224,3.364,3.954,4.004,3.940,3.260,3.153,2.808,2.511},Reflectance=[181]{28.000,39.000,43.000,42.000,40.000,43.000,46.000,45.000,45.000,48.000,50.000,44.000,42.000,47.000,46.000,45.000,44.000,48.000,50.000,51.000,51.000,50.000,49.000,46.000,50.000,49.000,47.000,49.000,54.000,54.000,53.000,51.000,54.000,54.000,54.000,51.000,51.000,51.000,42.000,43.000,51.000,54.000,56.000,54.000,52.000,53.000,50.000,52.000,44.000,42.000,48.000,46.000,43.000,42.000,41.000,52.000,53.000,55.000,52.000,53.000,62.000,69.000,62.000,48.000,52.000,48.000,54.000,56.000,49.000,53.000,55.000,58.000,52.000,54.000,57.000,58.000,64.000,73.000,73.000,71.000,73.000,76.000,76.000,75.000,74.000,72.000,71.000,67.000,65.000,68.000,72.000,75.000,76.000,75.000,77.000,78.000,78.000,79.000,79.000,78.000,79.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,79.000,78.000,78.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,77.000,78.000,77.000,78.000,78.000,78.000,78.000,78.000,77.000,77.000,77.000,77.000,77.000,78.000,78.000,77.000,77.000,77.000,75.000,76.000,77.000,76.000,75.000,72.000,72.000,73.000,70.000,109.000,74.000,75.000,94.000,103.000,98.000,39.000,38.000,30.000,57.000,86.000,75.000,81.000,69.000,83.000,89.000,89.000,83.000}
diff --git a/ncd_parser/demo/demo.launch b/ncd_parser/demo/demo.launch
deleted file mode 100644
index fea5687..0000000
--- a/ncd_parser/demo/demo.launch
+++ /dev/null
@@ -1,9 +0,0 @@
-
-
-
-
-
-
-
diff --git a/ncd_parser/demo/demo.vcg b/ncd_parser/demo/demo.vcg
deleted file mode 100644
index e13fd29..0000000
--- a/ncd_parser/demo/demo.vcg
+++ /dev/null
@@ -1,49 +0,0 @@
-Background\ ColorR=0
-Background\ ColorG=0
-Background\ ColorB=0
-Fixed\ Frame=/map
-Target\ Frame=
-Left\ Laser\ Scan.Alpha=1
-Left\ Laser\ Scan.Billboard\ Size=0.01
-Left\ Laser\ Scan.Color\ Transformer=Height map
-Left\ Laser\ Scan.Decay\ Time=500
-Left\ Laser\ Scan.Enabled=1
-Left\ Laser\ Scan.Position\ Transformer=XYZ
-Left\ Laser\ Scan.Selectable=1
-Left\ Laser\ Scan.Style=1
-Left\ Laser\ Scan.Topic=scan
-Left\ Laser\ Scan..Flat\ ColorColorR=1
-Left\ Laser\ Scan..Flat\ ColorColorG=1
-Left\ Laser\ Scan..Flat\ ColorColorB=1
-Left\ Laser\ Scan..Height\ mapAutocompute\ Height\ Bounds=0
-Left\ Laser\ Scan..Height\ mapMax\ Height=6
-Left\ Laser\ Scan..Height\ mapMin\ Height=-2
-Left\ Laser\ Scan..IntensityAutocompute\ Intensity\ Bounds=1
-Left\ Laser\ Scan..IntensityMax\ ColorR=1
-Left\ Laser\ Scan..IntensityMax\ ColorG=0
-Left\ Laser\ Scan..IntensityMax\ ColorB=0
-Left\ Laser\ Scan..IntensityMax\ Intensity=108
-Left\ Laser\ Scan..IntensityMin\ ColorR=1
-Left\ Laser\ Scan..IntensityMin\ ColorG=1
-Left\ Laser\ Scan..IntensityMin\ ColorB=0
-Left\ Laser\ Scan..IntensityMin\ Intensity=27
-TF.All\ Enabled=0
-TF.Enabled=0
-TF.Frame\ Timeout=15
-TF.Show\ Arrows=1
-TF.Show\ Axes=1
-TF.Show\ Names=1
-TF.Update\ Interval=0
-Tool\ 2D\ Nav\ GoalTopic=goal
-Tool\ 2D\ Pose\ EstimateTopic=initialpose
-Camera\ Type=rviz::OrbitViewController
-Camera\ Config=1.34552 4.91839 7.01259 -22.3902 1.6998 -4.07936
-Property\ Grid\ State=selection=Left Laser Scan.Enabled;expanded=.Global Options,TF.Enabled.TF.StatusTopStatus,TF.Enabled.TF.Tree,Left Laser Scan.Enabled;scrollpos=0,0;splitterpos=133,266;ispageselected=1
-[Display0]
-Name=TF
-Package=rviz
-ClassName=rviz::TFDisplay
-[Display1]
-Name=Left Laser Scan
-Package=rviz
-ClassName=rviz::LaserScanDisplay
diff --git a/ncd_parser/include/ncd_parser/ncd_parser.h b/ncd_parser/include/ncd_parser/ncd_parser.h
deleted file mode 100644
index 71b8d23..0000000
--- a/ncd_parser/include/ncd_parser/ncd_parser.h
+++ /dev/null
@@ -1,93 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#ifndef NCD_PARSER_NCD_PARSER
-#define NCD_PARSER_NCD_PARSER
-
-#include
-#include
-
-#include
-#include
-#include
-
-const double DEG_TO_RAD = 3.14159 / 180.0;
-
-const double RANGE_MIN = 0.20;
-const double RANGE_MAX = 50.0;
-
-const std::string worldFrame_ = "map";
-const std::string odomFrame_ = "odom";
-const std::string leftLaserFrame_ = "laser_left";
-const std::string rightLaserFrame_ = "laser_right";
-
-class NCDParser
-{
- private:
-
- char* filename_;
- double rate_;
- double start_, end_;
- double lastTime_;
-
- ros::Publisher leftLaserPublisher_;
- ros::Publisher rightLaserPublisher_;
-
- tf::TransformBroadcaster tfBroadcaster_;
-
- tf::Transform worldToOdom_;
- tf::Transform odomToLeftLaser_;
- tf::Transform odomToRightLaser_;
-
- void publishLaserMessage(const std::vector& tokens,
- const std::string& laserFrame,
- const ros::Publisher& publisher);
-
- void publishTfMessages(const std::vector& tokens);
-
- void tokenize (const std::string& str,
- std::vector &tokens,
- std::string sentinel);
-
- std::vector extractArray(std::string s, std::string pattern);
-
- double extractValue(std::string s, std::string pattern);
-
- void createOdomToLeftLaserTf();
- void createOdomToRightLaserTf();
-
- public:
-
- NCDParser(char* filename);
- virtual ~NCDParser();
-
- void launch();
-};
-
-#endif
diff --git a/ncd_parser/package.xml b/ncd_parser/package.xml
deleted file mode 100644
index 0f680f2..0000000
--- a/ncd_parser/package.xml
+++ /dev/null
@@ -1,24 +0,0 @@
-
- ncd_parser
- 0.3.3
-
- The ncd_parser package reads in .alog data files from the New College Dataset and broadcasts scan and odometry messages to ROS.
-
- Ivan Dryanovski
- Carlos
-
- http://wiki.ros.org/ncd_parser
- Ivan Dryanovski
- BSD
-
- catkin
-
- roscpp
- sensor_msgs
- tf
-
- roscpp
- sensor_msgs
- tf
-
-
diff --git a/ncd_parser/src/ncd_parser.cpp b/ncd_parser/src/ncd_parser.cpp
deleted file mode 100644
index 9837686..0000000
--- a/ncd_parser/src/ncd_parser.cpp
+++ /dev/null
@@ -1,283 +0,0 @@
-/*
- * Copyright (c) 2011, Ivan Dryanovski, William Morris
- * All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
- *
- * * Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the CCNY Robotics Lab nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-#include "ncd_parser/ncd_parser.h"
-
-int main(int argc, char** argv)
-{
- if(argc != 4)
- {
- printf("usage is `rosrun ncd_parser ncd_parser filename.alog`\n");
- return 1;
- }
-
- ros::init (argc, argv, "ncd_parser");
- NCDParser parser(argv[1]);
- sleep(2);
- parser.launch();
- return 0;
-}
-
-NCDParser::NCDParser(char* filename):filename_(filename)
-{
- ROS_INFO ("Starting NCDParser");
-
- ros::NodeHandle nh;
- ros::NodeHandle nh_private ("~");
-
- createOdomToLeftLaserTf();
- createOdomToRightLaserTf();
- lastTime_ = -1;
-
- // **** parameters
-
- if (!nh_private.getParam ("start", start_))
- start_ = 0.0;
- if (!nh_private.getParam ("end", end_))
- end_ = -1;
- if (!nh_private.getParam ("rate", rate_))
- rate_ = 1.0;
-
- if (rate_ == 0) ROS_FATAL("rate parameter cannot be 0");
-
- // **** topics
-
- leftLaserPublisher_ = nh.advertise("scan", 100);
- rightLaserPublisher_ = nh.advertise("scan", 100);
-}
-
-NCDParser::~NCDParser()
-{
- ROS_INFO ("Shutting down NCDParser");
-}
-
-void NCDParser::launch()
-{
- std::ifstream aLogFile;
- aLogFile.open(filename_);
-
- if(!aLogFile.is_open())
- ROS_FATAL("Could not open %s\n", filename_);
-
- int lineCounter = 0;
- std::string line;
-
- // **** skip first lines
-
- for (int i = 0; i < 210; i++)
- {
- getline(aLogFile, line);
- lineCounter++;
- }
-
- // **** iterate over rest of file
-
- while (getline(aLogFile, line))
- {
- lineCounter++;
- std::vector tokens;
- tokenize(line, tokens, " ");
-
- // skip incomplete line
- if (tokens.size() < 4) continue;
-
- // skip log entries before start time
- if (strtod(tokens[0].c_str(), NULL) <= start_) continue;
-
- // stop if time is bigger than end point time
- if (strtod(tokens[0].c_str(), NULL) > end_ && end_ != -1)
- {
- std::cout << strtod(tokens[0].c_str(), NULL) << ", " << end_ << std::endl;
- ROS_INFO("Reached specified end time.");
- break;
- }
-
- // publish messages
- if (tokens[1].compare("LMS_LASER_2D_LEFT") == 0)
- publishLaserMessage(tokens, leftLaserFrame_, leftLaserPublisher_);
- else if (tokens[1].compare("LMS_LASER_2D_RIGHT") == 0)
- publishLaserMessage(tokens, rightLaserFrame_, rightLaserPublisher_);
- else if (tokens[1].compare("ODOMETRY_POSE") == 0)
- publishTfMessages(tokens);
- else
- continue;
-
- // wait before publishing next message
-
- double time = extractValue(tokens[3], "time=");
-
- if(lastTime_ == -1) lastTime_ = time;
- else
- {
- ros::Duration d = (ros::Time(time) - ros::Time(lastTime_)) * ( 1.0 / rate_);
- lastTime_ = time;
- if (d.toNSec() > 0) d.sleep();
- }
- }
-}
-
-void NCDParser::publishLaserMessage(const std::vector& tokens,
- const std::string& laserFrame,
- const ros::Publisher& publisher)
-{
- ROS_DEBUG("Laser message");
-
- sensor_msgs::LaserScan scan;
-
- double time = extractValue(tokens[3], "time=");
-
- scan.header.stamp = ros::Time(time);
- scan.header.frame_id = laserFrame;
-
- scan.angle_min = extractValue(tokens[3], "minAngle=") * DEG_TO_RAD;
- scan.angle_max = extractValue(tokens[3], "maxAngle=") * DEG_TO_RAD;
- scan.angle_increment = extractValue(tokens[3], "angRes=") * DEG_TO_RAD;
- scan.range_min = RANGE_MIN;
- scan.range_max = RANGE_MAX;
- scan.ranges = extractArray(tokens[3], "Range=[181]");
- scan.intensities = extractArray(tokens[3], "Reflectance=[181]");
-
- publisher.publish(scan);
-}
-
-void NCDParser::publishTfMessages(const std::vector& tokens)
-{
- ROS_DEBUG("Tf message");
-
- // extract time
- double time = extractValue(tokens[3], "time=");
-
- // extract x, y, theta
- std::vector xytheta = extractArray(tokens[3], "Pose=[3x1]");
- double x = xytheta[0];
- double y = xytheta[1];
- double z = 0.0;
- double theta = xytheta[2];
-
- // extract Pitch
- double pitch = extractValue(tokens[3], "Pitch=");
-
- // extract Roll
- double roll = extractValue(tokens[3], "Roll=");
-
- tf::Quaternion rotation;
- rotation.setRPY (roll, pitch, theta);
- worldToOdom_.setRotation (rotation);
-
- tf::Vector3 origin;
- origin.setValue (x, y, z);
- worldToOdom_.setOrigin (origin);
-
- tf::StampedTransform worldToOdomStamped(worldToOdom_, ros::Time(time), worldFrame_, odomFrame_);
- tfBroadcaster_.sendTransform(worldToOdomStamped);
-
- tf::StampedTransform odomToLeftLaserStamped(odomToLeftLaser_, ros::Time(time), odomFrame_, leftLaserFrame_);
- tfBroadcaster_.sendTransform(odomToLeftLaserStamped);
-
- tf::StampedTransform odomToRightLaserStamped(odomToRightLaser_, ros::Time(time), odomFrame_, rightLaserFrame_);
- tfBroadcaster_.sendTransform(odomToRightLaserStamped);
-}
-
-void NCDParser::tokenize (const std::string& str,
- std::vector &tokens,
- std::string sentinel)
-{
- std::string::size_type lastPos = str.find_first_not_of (sentinel, 0);
- std::string::size_type pos = str.find_first_of (sentinel, lastPos);
-
- while (std::string::npos != pos || std::string::npos != lastPos)
- {
- std::string stringToken = str.substr (lastPos, pos - lastPos);
- tokens.push_back (stringToken);
- lastPos = str.find_first_not_of (sentinel, pos);
- pos = str.find_first_of (sentinel, lastPos);
- }
-}
-
-std::vector NCDParser::extractArray(std::string s, std::string pattern)
-{
- int n0 = s.find(pattern);
- int n1 = s.find("{", n0);
- int n2 = s.find("}", n1);
- std::string valueList = s.substr(n1+1, n2-n1-1);
-
- std::vector values;
- std::vector s_values;
- tokenize(valueList, s_values, ",");
-
- for (unsigned int i = 0; i < s_values.size(); i++)
- values.push_back(strtod(s_values[i].c_str(), NULL));
-
- return values;
-}
-
-double NCDParser::extractValue(std::string s, std::string pattern)
-{
- int n1 = s.find(pattern);
- int n2 = s.find(",", n1);
- std::string s_value = s.substr(n1+pattern.length(), n2-n1-pattern.length());
- return strtod(s_value.c_str(), NULL);
-}
-
-
-void NCDParser::createOdomToLeftLaserTf()
-{
- double x = -0.270;
- double y = -0.030;
- double z = 0.495;
- double roll = 180.0 * DEG_TO_RAD;
- double pitch = 90.0 * DEG_TO_RAD;
- double yaw = -90.0 * DEG_TO_RAD;
-
- tf::Quaternion rotation;
- rotation.setRPY (roll, pitch, yaw);
- odomToLeftLaser_.setRotation (rotation);
-
- tf::Vector3 origin;
- origin.setValue (x, y, z);
- odomToLeftLaser_.setOrigin (origin);
-}
-
-void NCDParser::createOdomToRightLaserTf()
-{
- double x = 0.270;
- double y = -0.030;
- double z = 0.495;
- double roll = 90.0 * DEG_TO_RAD;
- double pitch = -90.0 * DEG_TO_RAD;
- double yaw = 180.0 * DEG_TO_RAD;
-
- tf::Quaternion rotation;
- rotation.setRPY (roll, pitch, yaw);
- odomToRightLaser_.setRotation (rotation);
-
- tf::Vector3 origin;
- origin.setValue (x, y, z);
- odomToRightLaser_.setOrigin (origin);
-}
diff --git a/polar_scan_matcher/CHANGELOG.rst b/polar_scan_matcher/CHANGELOG.rst
deleted file mode 100644
index 866e938..0000000
--- a/polar_scan_matcher/CHANGELOG.rst
+++ /dev/null
@@ -1,26 +0,0 @@
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-Changelog for package polar_scan_matcher
-^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
-
-0.3.3 (2021-02-15)
-------------------
-
-0.3.2 (2016-03-19)
-------------------
-
-0.3.1 (2015-12-18)
-------------------
-
-0.3.0 (2015-11-10)
-------------------
-
-0.2.1 (2015-10-14)
-------------------
-* [feat] added polar scan matcher
-* [feat] added imu option to PSM, made CSM and PSM look similar
-* [feat] added demo dir to CSM,
-* [fix] PSM launch file
-* [sys] ROS Hydro compatible
-* [sys] Cleaning
-* [sys] correct license and references to PSM and CSM
-* Contributors: Daniel Axtens, Ivan Dryanovski
diff --git a/polar_scan_matcher/CMakeLists.txt b/polar_scan_matcher/CMakeLists.txt
deleted file mode 100644
index 0677241..0000000
--- a/polar_scan_matcher/CMakeLists.txt
+++ /dev/null
@@ -1,45 +0,0 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(polar_scan_matcher)
-
-set( ROS_CXX_DEPENDENCIES
- roscpp
- tf
- sensor_msgs
- geometry_msgs)
-
-find_package(catkin REQUIRED COMPONENTS ${ROS_CXX_DEPENDENCIES})
-
-include_directories(include ${catkin_INCLUDE_DIRS})
-
-catkin_package(
- INCLUDE_DIRS include
- LIBRARIES polar_scan_matcher
- CATKIN_DEPENDS ${ROSS_CXX_DEPENDENCIES}
-)
-
-add_library(polar_scan_matcher src/polar_match.cpp)
-
-add_executable(psm_node src/psm_node.cpp)
-target_link_libraries(psm_node polar_scan_matcher
- ${catkin_LIBRARIES})
-
-install(TARGETS polar_scan_matcher
- ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
- RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
-
-#Install library includes
-install(DIRECTORY include/polar_scan_matcher/
- DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} )
-
-install(TARGETS psm_node
- DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
-
-#set the default path for built executables to the "bin" directory
-#set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
-#set the default path for built libraries to the "lib" directory
-#set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
-
-#rosbuild_add_executable(polar_scan_matcher src/psm_node.cpp
-# src/polar_match.cpp)
-
diff --git a/polar_scan_matcher/COPYING b/polar_scan_matcher/COPYING
deleted file mode 100644
index d60c31a..0000000
--- a/polar_scan_matcher/COPYING
+++ /dev/null
@@ -1,340 +0,0 @@
- GNU GENERAL PUBLIC LICENSE
- Version 2, June 1991
-
- Copyright (C) 1989, 1991 Free Software Foundation, Inc.
- 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
- Everyone is permitted to copy and distribute verbatim copies
- of this license document, but changing it is not allowed.
-
- Preamble
-
- The licenses for most software are designed to take away your
-freedom to share and change it. By contrast, the GNU General Public
-License is intended to guarantee your freedom to share and change free
-software--to make sure the software is free for all its users. This
-General Public License applies to most of the Free Software
-Foundation's software and to any other program whose authors commit to
-using it. (Some other Free Software Foundation software is covered by
-the GNU Library General Public License instead.) You can apply it to
-your programs, too.
-
- When we speak of free software, we are referring to freedom, not
-price. Our General Public Licenses are designed to make sure that you
-have the freedom to distribute copies of free software (and charge for
-this service if you wish), that you receive source code or can get it
-if you want it, that you can change the software or use pieces of it
-in new free programs; and that you know you can do these things.
-
- To protect your rights, we need to make restrictions that forbid
-anyone to deny you these rights or to ask you to surrender the rights.
-These restrictions translate to certain responsibilities for you if you
-distribute copies of the software, or if you modify it.
-
- For example, if you distribute copies of such a program, whether
-gratis or for a fee, you must give the recipients all the rights that
-you have. You must make sure that they, too, receive or can get the
-source code. And you must show them these terms so they know their
-rights.
-
- We protect your rights with two steps: (1) copyright the software, and
-(2) offer you this license which gives you legal permission to copy,
-distribute and/or modify the software.
-
- Also, for each author's protection and ours, we want to make certain
-that everyone understands that there is no warranty for this free
-software. If the software is modified by someone else and passed on, we
-want its recipients to know that what they have is not the original, so
-that any problems introduced by others will not reflect on the original
-authors' reputations.
-
- Finally, any free program is threatened constantly by software
-patents. We wish to avoid the danger that redistributors of a free
-program will individually obtain patent licenses, in effect making the
-program proprietary. To prevent this, we have made it clear that any
-patent must be licensed for everyone's free use or not licensed at all.
-
- The precise terms and conditions for copying, distribution and
-modification follow.
-
- GNU GENERAL PUBLIC LICENSE
- TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
-
- 0. This License applies to any program or other work which contains
-a notice placed by the copyright holder saying it may be distributed
-under the terms of this General Public License. The "Program", below,
-refers to any such program or work, and a "work based on the Program"
-means either the Program or any derivative work under copyright law:
-that is to say, a work containing the Program or a portion of it,
-either verbatim or with modifications and/or translated into another
-language. (Hereinafter, translation is included without limitation in
-the term "modification".) Each licensee is addressed as "you".
-
-Activities other than copying, distribution and modification are not
-covered by this License; they are outside its scope. The act of
-running the Program is not restricted, and the output from the Program
-is covered only if its contents constitute a work based on the
-Program (independent of having been made by running the Program).
-Whether that is true depends on what the Program does.
-
- 1. You may copy and distribute verbatim copies of the Program's
-source code as you receive it, in any medium, provided that you
-conspicuously and appropriately publish on each copy an appropriate
-copyright notice and disclaimer of warranty; keep intact all the
-notices that refer to this License and to the absence of any warranty;
-and give any other recipients of the Program a copy of this License
-along with the Program.
-
-You may charge a fee for the physical act of transferring a copy, and
-you may at your option offer warranty protection in exchange for a fee.
-
- 2. You may modify your copy or copies of the Program or any portion
-of it, thus forming a work based on the Program, and copy and
-distribute such modifications or work under the terms of Section 1
-above, provided that you also meet all of these conditions:
-
- a) You must cause the modified files to carry prominent notices
- stating that you changed the files and the date of any change.
-
- b) You must cause any work that you distribute or publish, that in
- whole or in part contains or is derived from the Program or any
- part thereof, to be licensed as a whole at no charge to all third
- parties under the terms of this License.
-
- c) If the modified program normally reads commands interactively
- when run, you must cause it, when started running for such
- interactive use in the most ordinary way, to print or display an
- announcement including an appropriate copyright notice and a
- notice that there is no warranty (or else, saying that you provide
- a warranty) and that users may redistribute the program under
- these conditions, and telling the user how to view a copy of this
- License. (Exception: if the Program itself is interactive but
- does not normally print such an announcement, your work based on
- the Program is not required to print an announcement.)
-
-These requirements apply to the modified work as a whole. If
-identifiable sections of that work are not derived from the Program,
-and can be reasonably considered independent and separate works in
-themselves, then this License, and its terms, do not apply to those
-sections when you distribute them as separate works. But when you
-distribute the same sections as part of a whole which is a work based
-on the Program, the distribution of the whole must be on the terms of
-this License, whose permissions for other licensees extend to the
-entire whole, and thus to each and every part regardless of who wrote it.
-
-Thus, it is not the intent of this section to claim rights or contest
-your rights to work written entirely by you; rather, the intent is to
-exercise the right to control the distribution of derivative or
-collective works based on the Program.
-
-In addition, mere aggregation of another work not based on the Program
-with the Program (or with a work based on the Program) on a volume of
-a storage or distribution medium does not bring the other work under
-the scope of this License.
-
- 3. You may copy and distribute the Program (or a work based on it,
-under Section 2) in object code or executable form under the terms of
-Sections 1 and 2 above provided that you also do one of the following:
-
- a) Accompany it with the complete corresponding machine-readable
- source code, which must be distributed under the terms of Sections
- 1 and 2 above on a medium customarily used for software interchange; or,
-
- b) Accompany it with a written offer, valid for at least three
- years, to give any third party, for a charge no more than your
- cost of physically performing source distribution, a complete
- machine-readable copy of the corresponding source code, to be
- distributed under the terms of Sections 1 and 2 above on a medium
- customarily used for software interchange; or,
-
- c) Accompany it with the information you received as to the offer
- to distribute corresponding source code. (This alternative is
- allowed only for noncommercial distribution and only if you
- received the program in object code or executable form with such
- an offer, in accord with Subsection b above.)
-
-The source code for a work means the preferred form of the work for
-making modifications to it. For an executable work, complete source
-code means all the source code for all modules it contains, plus any
-associated interface definition files, plus the scripts used to
-control compilation and installation of the executable. However, as a
-special exception, the source code distributed need not include
-anything that is normally distributed (in either source or binary
-form) with the major components (compiler, kernel, and so on) of the
-operating system on which the executable runs, unless that component
-itself accompanies the executable.
-
-If distribution of executable or object code is made by offering
-access to copy from a designated place, then offering equivalent
-access to copy the source code from the same place counts as
-distribution of the source code, even though third parties are not
-compelled to copy the source along with the object code.
-
- 4. You may not copy, modify, sublicense, or distribute the Program
-except as expressly provided under this License. Any attempt
-otherwise to copy, modify, sublicense or distribute the Program is
-void, and will automatically terminate your rights under this License.
-However, parties who have received copies, or rights, from you under
-this License will not have their licenses terminated so long as such
-parties remain in full compliance.
-
- 5. You are not required to accept this License, since you have not
-signed it. However, nothing else grants you permission to modify or
-distribute the Program or its derivative works. These actions are
-prohibited by law if you do not accept this License. Therefore, by
-modifying or distributing the Program (or any work based on the
-Program), you indicate your acceptance of this License to do so, and
-all its terms and conditions for copying, distributing or modifying
-the Program or works based on it.
-
- 6. Each time you redistribute the Program (or any work based on the
-Program), the recipient automatically receives a license from the
-original licensor to copy, distribute or modify the Program subject to
-these terms and conditions. You may not impose any further
-restrictions on the recipients' exercise of the rights granted herein.
-You are not responsible for enforcing compliance by third parties to
-this License.
-
- 7. If, as a consequence of a court judgment or allegation of patent
-infringement or for any other reason (not limited to patent issues),
-conditions are imposed on you (whether by court order, agreement or
-otherwise) that contradict the conditions of this License, they do not
-excuse you from the conditions of this License. If you cannot
-distribute so as to satisfy simultaneously your obligations under this
-License and any other pertinent obligations, then as a consequence you
-may not distribute the Program at all. For example, if a patent
-license would not permit royalty-free redistribution of the Program by
-all those who receive copies directly or indirectly through you, then
-the only way you could satisfy both it and this License would be to
-refrain entirely from distribution of the Program.
-
-If any portion of this section is held invalid or unenforceable under
-any particular circumstance, the balance of the section is intended to
-apply and the section as a whole is intended to apply in other
-circumstances.
-
-It is not the purpose of this section to induce you to infringe any
-patents or other property right claims or to contest validity of any
-such claims; this section has the sole purpose of protecting the
-integrity of the free software distribution system, which is
-implemented by public license practices. Many people have made
-generous contributions to the wide range of software distributed
-through that system in reliance on consistent application of that
-system; it is up to the author/donor to decide if he or she is willing
-to distribute software through any other system and a licensee cannot
-impose that choice.
-
-This section is intended to make thoroughly clear what is believed to
-be a consequence of the rest of this License.
-
- 8. If the distribution and/or use of the Program is restricted in
-certain countries either by patents or by copyrighted interfaces, the
-original copyright holder who places the Program under this License
-may add an explicit geographical distribution limitation excluding
-those countries, so that distribution is permitted only in or among
-countries not thus excluded. In such case, this License incorporates
-the limitation as if written in the body of this License.
-
- 9. The Free Software Foundation may publish revised and/or new versions
-of the General Public License from time to time. Such new versions will
-be similar in spirit to the present version, but may differ in detail to
-address new problems or concerns.
-
-Each version is given a distinguishing version number. If the Program
-specifies a version number of this License which applies to it and "any
-later version", you have the option of following the terms and conditions
-either of that version or of any later version published by the Free
-Software Foundation. If the Program does not specify a version number of
-this License, you may choose any version ever published by the Free Software
-Foundation.
-
- 10. If you wish to incorporate parts of the Program into other free
-programs whose distribution conditions are different, write to the author
-to ask for permission. For software which is copyrighted by the Free
-Software Foundation, write to the Free Software Foundation; we sometimes
-make exceptions for this. Our decision will be guided by the two goals
-of preserving the free status of all derivatives of our free software and
-of promoting the sharing and reuse of software generally.
-
- NO WARRANTY
-
- 11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY
-FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN
-OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES
-PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED
-OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
-MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS
-TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE
-PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING,
-REPAIR OR CORRECTION.
-
- 12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
-WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR
-REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES,
-INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING
-OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED
-TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY
-YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER
-PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE
-POSSIBILITY OF SUCH DAMAGES.
-
- END OF TERMS AND CONDITIONS
-
- How to Apply These Terms to Your New Programs
-
- If you develop a new program, and you want it to be of the greatest
-possible use to the public, the best way to achieve this is to make it
-free software which everyone can redistribute and change under these terms.
-
- To do so, attach the following notices to the program. It is safest
-to attach them to the start of each source file to most effectively
-convey the exclusion of warranty; and each file should have at least
-the "copyright" line and a pointer to where the full notice is found.
-
-
- Copyright (C)
-
- This program is free software; you can redistribute it and/or modify
- it under the terms of the GNU General Public License as published by
- the Free Software Foundation; either version 2 of the License, or
- (at your option) any later version.
-
- This program is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- GNU General Public License for more details.
-
- You should have received a copy of the GNU General Public License
- along with this program; if not, write to the Free Software
- Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
-
-
-Also add information on how to contact you by electronic and paper mail.
-
-If the program is interactive, make it output a short notice like this
-when it starts in an interactive mode:
-
- Gnomovision version 69, Copyright (C) year name of author
- Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
- This is free software, and you are welcome to redistribute it
- under certain conditions; type `show c' for details.
-
-The hypothetical commands `show w' and `show c' should show the appropriate
-parts of the General Public License. Of course, the commands you use may
-be called something other than `show w' and `show c'; they could even be
-mouse-clicks or menu items--whatever suits your program.
-
-You should also get your employer (if you work as a programmer) or your
-school, if any, to sign a "copyright disclaimer" for the program, if
-necessary. Here is a sample; alter the names:
-
- Yoyodyne, Inc., hereby disclaims all copyright interest in the program
- `Gnomovision' (which makes passes at compilers) written by James Hacker.
-
- , 1 April 1989
- Ty Coon, President of Vice
-
-This General Public License does not permit incorporating your program into
-proprietary programs. If your program is a subroutine library, you may
-consider it more useful to permit linking proprietary applications with the
-library. If this is what you want to do, use the GNU Library General
-Public License instead of this License.
diff --git a/polar_scan_matcher/README b/polar_scan_matcher/README
deleted file mode 100644
index 0cdb9a3..0000000
--- a/polar_scan_matcher/README
+++ /dev/null
@@ -1,6 +0,0 @@
-A Polar Scan Matcher [1] package for ROS. The package can be used to produce a
-pose estimate for a robot when no odometry is available.
-
-[1] A. Diosi and L. Kleeman, "Laser Scan Matching in Polar Coordinates with
-Application to SLAM " Proceedings of 2005 IEEE/RSJ International Conference
-on Intelligent Robots and Systems, August, 2005, Edmonton, Canada
diff --git a/polar_scan_matcher/demo/demo.bag b/polar_scan_matcher/demo/demo.bag
deleted file mode 100644
index 9f753c1..0000000
Binary files a/polar_scan_matcher/demo/demo.bag and /dev/null differ
diff --git a/polar_scan_matcher/demo/demo.launch b/polar_scan_matcher/demo/demo.launch
deleted file mode 100644
index 207bf63..0000000
--- a/polar_scan_matcher/demo/demo.launch
+++ /dev/null
@@ -1,19 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/polar_scan_matcher/demo/demo.rviz b/polar_scan_matcher/demo/demo.rviz
deleted file mode 100644
index 7dd8ad9..0000000
--- a/polar_scan_matcher/demo/demo.rviz
+++ /dev/null
@@ -1,161 +0,0 @@
-Panels:
- - Class: rviz/Displays
- Help Height: 78
- Name: Displays
- Property Tree Widget:
- Expanded:
- - /Global Options1
- - /Status1
- - /LaserScan1
- - /TF1
- - /TF1/Frames1
- Splitter Ratio: 0.5
- Tree Height: 434
- - Class: rviz/Selection
- Name: Selection
- - Class: rviz/Tool Properties
- Expanded:
- - /2D Pose Estimate1
- - /2D Nav Goal1
- - /Publish Point1
- Name: Tool Properties
- Splitter Ratio: 0.588679
- - Class: rviz/Views
- Expanded:
- - /Current View1
- Name: Views
- Splitter Ratio: 0.5
- - Class: rviz/Time
- Experimental: false
- Name: Time
- SyncMode: 0
- SyncSource: LaserScan
-Visualization Manager:
- Class: ""
- Displays:
- - Alpha: 0.5
- Cell Size: 1
- Class: rviz/Grid
- Color: 160; 160; 164
- Enabled: true
- Line Style:
- Line Width: 0.03
- Value: Lines
- Name: Grid
- Normal Cell Count: 0
- Offset:
- X: 0
- Y: 0
- Z: 0
- Plane: XY
- Plane Cell Count: 10
- Reference Frame:
- Value: true
- - Alpha: 1
- Autocompute Intensity Bounds: true
- Autocompute Value Bounds:
- Max Value: 10
- Min Value: -10
- Value: true
- Axis: Z
- Channel Name: intensity
- Class: rviz/LaserScan
- Color: 255; 0; 0
- Color Transformer: FlatColor
- Decay Time: 0
- Enabled: true
- Invert Rainbow: false
- Max Color: 255; 255; 255
- Max Intensity: 4096
- Min Color: 0; 0; 0
- Min Intensity: 0
- Name: LaserScan
- Position Transformer: XYZ
- Queue Size: 10
- Selectable: true
- Size (Pixels): 3
- Size (m): 0.01
- Style: Flat Squares
- Topic: /scan
- Use Fixed Frame: true
- Use rainbow: true
- Value: true
- - Class: rviz/TF
- Enabled: true
- Frame Timeout: 15
- Frames:
- All Enabled: true
- base_link:
- Value: true
- laser:
- Value: true
- world:
- Value: true
- Marker Scale: 1
- Name: TF
- Show Arrows: true
- Show Axes: true
- Show Names: true
- Tree:
- world:
- base_link:
- laser:
- {}
- Update Interval: 0
- Value: true
- Enabled: true
- Global Options:
- Background Color: 48; 48; 48
- Fixed Frame: world
- Frame Rate: 30
- Name: root
- Tools:
- - Class: rviz/Interact
- Hide Inactive Objects: true
- - Class: rviz/MoveCamera
- - Class: rviz/Select
- - Class: rviz/FocusCamera
- - Class: rviz/Measure
- - Class: rviz/SetInitialPose
- Topic: /initialpose
- - Class: rviz/SetGoal
- Topic: /move_base_simple/goal
- - Class: rviz/PublishPoint
- Single click: true
- Topic: /clicked_point
- Value: true
- Views:
- Current:
- Angle: 0
- Class: rviz/TopDownOrtho
- Enable Stereo Rendering:
- Stereo Eye Separation: 0.06
- Stereo Focal Distance: 1
- Swap Stereo Eyes: false
- Value: false
- Name: Current View
- Near Clip Distance: 0.01
- Scale: 100
- Target Frame:
- Value: TopDownOrtho (rviz)
- X: 0
- Y: 0
- Saved: ~
-Window Geometry:
- Displays:
- collapsed: false
- Height: 721
- Hide Left Dock: false
- Hide Right Dock: false
- QMainWindow State: 000000ff00000000fd00000004000000000000013c0000023dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000360000023d000000b700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000023dfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000360000023d0000009b00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004000000003efc0100000002fb0000000800540069006d00650100000000000004000000024500fffffffb0000000800540069006d00650100000000000004500000000000000000000004000000023d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
- Selection:
- collapsed: false
- Time:
- collapsed: false
- Tool Properties:
- collapsed: false
- Views:
- collapsed: false
- Width: 1024
- X: 0
- Y: 0
diff --git a/polar_scan_matcher/include/polar_scan_matcher/polar_match.h b/polar_scan_matcher/include/polar_scan_matcher/polar_match.h
deleted file mode 100644
index 828d2f4..0000000
--- a/polar_scan_matcher/include/polar_scan_matcher/polar_match.h
+++ /dev/null
@@ -1,183 +0,0 @@
-/***************************************************************************
- polar_match.h - matching laser scans in polar coord system
- designed for use with SICK LMS in cm res./361 meas. mode
- only 181 readings (1 deg res) are used (less accuracy but higher
- speed)
- -------------------
- begin : Tue Nov 9 2004
- version : 0.2
- copyright : (C) 2005 by Albert Diosi and Lindsay Kleeman
- email : albert.diosi@gmail.com
- comments : range units are cm; angle units are deg
- the laser is on the robots y axis
- - in scan projections, occluded ref scanpoints aren't removed!
- changed:
- 14/03/2005 removing of unnecessary code
- ***************************************************************************/
- /****************************************************************************
- This file is part of polar_matching.
-
- polar_matching is free software; you can redistribute it and/or modify
- it under the terms of the GNU General Public License as published by
- the Free Software Foundation; either version 2 of the License, or
- (at your option) any later version.
-
- polar_matching is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- GNU General Public License for more details.
-
- You should have received a copy of the GNU General Public License
- along with polar_matching; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
-****************************************************************************/
-
-#ifndef POLAR_SCAN_MATCHING_POLAR_MATCHER_H
-#define POLAR_SCAN_MATCHING_POLAR_MATCHER_H
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
-#define PM_TYPE double // change it to double for higher accuracy and lower speed
-
-// range reading errors
-#define PM_RANGE 1 // range reading is longer than PM_MAX_RANGE
-#define PM_MOVING 2 // range reading corresponds to a moving point
-#define PM_MIXED 4 // range reading is a mixed pixel
-#define PM_OCCLUDED 8 // range reading is occluded
-#define PM_EMPTY 16 // at that bearing there is no measurment (between 2
- // segments there is no interpolation!)
-
-#define PM_ODO -1 //show results with odometry only in mapping_with_matching()
-#define PM_PSM 1 //polar scanmatching - matching bearing
-#define PM_PSM_C 2 //polar scanmatching - using cartesian equations
-#define PM_ICP 3 //scanmatchign with iterative closest point
-#define PM_IDC 4 //lu's iterative dual correspondence - not implemented,
- //Guttman's external code is used for comparisson
-#define PM_MBICP 5 //scanmatchign with metric based ICP
-
-const double PM_D2R = M_PI/180.0; // degrees to rad
-const double PM_R2D = 180.0/M_PI; // rad to degrees
-
-//const int PM_L_POINTS = 681;
-
-//might want to consider doubles for rx,ry -> in a large environment?
-struct PMScan
-{
- PMScan(int nPoints)
- {
- r.resize(nPoints);
- x.resize(nPoints);
- y.resize(nPoints);
- bad.resize(nPoints);
- seg.resize(nPoints);
- }
-
- PM_TYPE rx; //robot odometry pos
- PM_TYPE ry; //robot odometry pos
- PM_TYPE th; //robot orientation
- std::vector r;//[cm] - 0 or negative ranges denote invalid readings.
- std::vector x;//[cm]
- std::vector y;//[cm]
- std::vector bad;// 0 if OK
- //sources of invalidity - too big range;
- //moving object; occluded;mixed pixel
- std::vector seg;//nuber describing into which segment the point belongs to
-};
-
-class PolarMatcher
-{
- private:
-
- //calculates an error index expressing the quality of the match
- //of the actual scan to the reference scan
- //has to be called after scan matching so the actual scan in expressed
- //in the reference scan coordinate system
- //return the average minimum Euclidean distance; MAXIMUM RANGE points
- //are not considered; number of non maximum range points have to be
- //smaller than a threshold
- PM_TYPE pm_error_index(PMScan *lsr,PMScan *lsa);
-
- //estimates the covariance matrix(c11,c12,c22,c33) (x,y,th) of
- //a scan match based on an error index (err-depends on how good the
- //match is), and the angle of the corridor if it is a corridor
- void pm_cov_est(PM_TYPE err, double *c11,double *c12, double *c22, double *c33,
- bool corridor=false, PM_TYPE corr_angle=0);
-
- void pm_scan_project(const PMScan *act, PM_TYPE *new_r, int *new_bad);
- PM_TYPE pm_orientation_search(const PMScan *ref, const PM_TYPE *new_r, const int *new_bad);
- PM_TYPE pm_translation_estimation(const PMScan *ref, const PM_TYPE *new_r, const int *new_bad, PM_TYPE C, PM_TYPE *dx, PM_TYPE *dy);
-
- PM_TYPE point_line_distance ( PM_TYPE x1, PM_TYPE y1, PM_TYPE x2, PM_TYPE y2,
- PM_TYPE x3, PM_TYPE y3,PM_TYPE *x, PM_TYPE *y);
-
- inline PM_TYPE norm_a ( PM_TYPE a )
- {
- int m;
- m= ( int ) ( a/ ( 2.0*M_PI ) );
- a=a- ( PM_TYPE ) m*M_PI;
- if ( a< ( -M_PI ) )
- a+=2.0*M_PI;
- if ( a>=M_PI )
- a-=2.0*M_PI;
- return ( a );
- }
-
- public:
-
- int PM_L_POINTS;
-
- PM_TYPE PM_FI_MIN;// = M_PI/2.0 - PM_FOV*PM_D2R/2.0;//[rad] bearing from which laser scans start
- PM_TYPE PM_FI_MAX;// = M_PI/2.0 + PM_FOV*PM_D2R/2.0;//[rad] bearing at which laser scans end
- PM_TYPE PM_DFI; // = PM_FOV*PM_D2R/ ( PM_L_POINTS + 1.0 );//[rad] angular resolution of laser scans
-
- std::vector pm_fi;//contains precomputed angles
- std::vector pm_si;//contains sinus of angles
- std::vector pm_co;//contains cos of angles
-
- double PM_FOV ; //! field of view of the laser range finder in degrees
- double PM_MAX_RANGE ; //![cm] max valid laser range (set this to about 400 for the Hokuyo URG)
- int PM_MIN_VALID_POINTS; //! minimum number of valid points for scanmatching
- int PM_SEARCH_WINDOW; //! half window size which is searched for correct orientation
-
- double PM_TIME_DELAY; //!<[ms]time delay (time registration error) in the laser measurements
-
- double PM_MAX_ERROR; //[cm] max distance between associated points used in pose est.
- double PM_STOP_COND; //! stopping condition; the pose change has to be smaller than ...
- int PM_MAX_ITER; //! maximum number of iterations for PSM.PSM_C
- int PM_MAX_ITER_ICP; //! maximum number of iterations for ICP,MBICP
- int PM_STOP_COND_ICP; //! stopping condition; the pose change has to be smaller than ... for ICP, MBICP
-
- PolarMatcher();
-
- void pm_init();
-
- //filters the ranges with a median filter. x,y points are not upadted
- //ls - laser scan; the job of the median filter is to remove chair and table
- //legs wich would be moving anyway;
- void pm_median_filter(PMScan *ls);
-
- // marks point further than a given distance PM_MAX_RANGE as PM_RANGE
- void pm_find_far_points(PMScan *ls);
-
- //segments scanpoints into groups based on range discontinuities
- void pm_segment_scan(PMScan *ls);
-
- // minimizes least square error through changing lsa->rx, lsa->ry,lsa->th
- // this looks for angle too, like pm_linearized_match_proper,execept it
- // fits a parabola to the error when searching for the angle and interpolates.
- PM_TYPE pm_psm(PMScan *lsr,PMScan *lsa);
-
- // does scan matching using the equations for translation and orietation
- //estimation as in Lu & milios, however our matching bearing association rule
- //is used together with our association filter.
- //this is PSM-C in the tech report
- PM_TYPE pm_psm_c(PMScan *lsr,PMScan *lsa);
-};
-
-#endif //POLAR_SCAN_MATCHING_POLAR_MATCH_H
diff --git a/polar_scan_matcher/include/polar_scan_matcher/psm_node.h b/polar_scan_matcher/include/polar_scan_matcher/psm_node.h
deleted file mode 100644
index 8007822..0000000
--- a/polar_scan_matcher/include/polar_scan_matcher/psm_node.h
+++ /dev/null
@@ -1,117 +0,0 @@
-/*
-* Polar Scan Matcher
-* Copyright (C) 2010, CCNY Robotics Lab
-* Ivan Dryanovski
-* William Morris
-* http://robotics.ccny.cuny.edu
-* Modified 2014, Daniel Axtens
-* whilst a student at the Australian National University
-*
-* This program is free software: you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as published by
-* the Free Software Foundation, either version 3 of the License, or
-* (at your option) any later version.
-*
-* This program is distributed in the hope that it will be useful,
-* but WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-* GNU General Public License for more details.
-*
-* You should have received a copy of the GNU General Public License
-* along with this program. If not, see .
-*
-* This is a wrapper around Polar Scan Matcher [1], written by
-* Albert Diosi
-*
-* [1] A. Diosi and L. Kleeman, "Laser Scan Matching in Polar Coordinates with
-* Application to SLAM " Proceedings of 2005 IEEE/RSJ International Conference
-* on Intelligent Robots and Systems, August, 2005, Edmonton, Canada
-*/
-
-#ifndef POLAR_SCAN_MATCHER_PSM_NODE_H
-#define POLAR_SCAN_MATCHER_PSM_NODE_H
-
-#include
-
-#include
-#include
-#include
-#include
-#include
-#include
-
-#include "polar_scan_matcher/polar_match.h"
-
-const std::string imuTopic_ = "imu";
-const std::string scanTopic_ = "scan";
-const std::string poseTopic_ = "pose2D";
-
-const double ROS_TO_PM = 100.0; // convert from cm to m
-
-class PSMNode
-{
- private:
-
- ros::Subscriber scanSubscriber_;
- ros::Subscriber imuSubscriber_;
- ros::Publisher posePublisher_;
-
- tf::TransformBroadcaster tfBroadcaster_;
- tf::TransformListener tfListener_;
- tf::Transform prevWorldToBase_;
- tf::Transform baseToLaser_;
- tf::Transform laserToBase_;
-
- bool initialized_;
- double totalDuration_;
- int scansCount_;
-
- PolarMatcher matcher_;
- PMScan * prevPMScan_;
-
- boost::mutex imuMutex_;
- double prevImuAngle_; // the yaw angle when we last perfomred a scan match
- double currImuAngle_; // the most recent yaw angle we have received
-
- // **** parameters
-
- bool publishTf_;
- bool publishPose_;
- bool useTfOdometry_;
- bool useImuOdometry_;
-
- int minValidPoints_;
- int searchWindow_;
- double maxError_;
- int maxIterations_;
- double stopCondition_;
-
- std::string worldFrame_;
- std::string baseFrame_;
- std::string laserFrame_;
-
- void getParams();
- bool initialize(const sensor_msgs::LaserScan& scan);
-
- void imuCallback (const sensor_msgs::Imu& imuMsg);
- void scanCallback (const sensor_msgs::LaserScan& scan);
-
- void publishTf(const tf::Transform& transform,
- const ros::Time& time);
- void publishPose(const tf::Transform& transform);
-
- void rosToPMScan(const sensor_msgs::LaserScan& scan,
- const tf::Transform& change,
- PMScan* pmScan);
- void pose2DToTf(const geometry_msgs::Pose2D& pose, tf::Transform& t);
- void tfToPose2D(const tf::Transform& t, geometry_msgs::Pose2D& pose);
- void getCurrentEstimatedPose(tf::Transform& worldToBase,
- const sensor_msgs::LaserScan& scanMsg);
-
- public:
-
- PSMNode();
- virtual ~PSMNode();
-};
-
-#endif // POLAR_SCAN_MATCHER_PSM_NODE_H
diff --git a/polar_scan_matcher/launch/psm.launch b/polar_scan_matcher/launch/psm.launch
deleted file mode 100644
index 0b55891..0000000
--- a/polar_scan_matcher/launch/psm.launch
+++ /dev/null
@@ -1,23 +0,0 @@
-
-
- /hokuyo_node/min_ang: -2.0862138271331787
- /hokuyo_node/max_ang: 2.0923497676849365
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/polar_scan_matcher/mainpage.dox b/polar_scan_matcher/mainpage.dox
deleted file mode 100644
index c4edc14..0000000
--- a/polar_scan_matcher/mainpage.dox
+++ /dev/null
@@ -1,26 +0,0 @@
-/**
-\mainpage
-\htmlinclude manifest.html
-
-\b polar_scan_matcher is ...
-
-
-
-
-\section codeapi Code API
-
-
-
-
-*/
diff --git a/polar_scan_matcher/package.xml b/polar_scan_matcher/package.xml
deleted file mode 100644
index 5206015..0000000
--- a/polar_scan_matcher/package.xml
+++ /dev/null
@@ -1,28 +0,0 @@
-
- polar_scan_matcher
- 0.3.3
-
-
- A wrapper around Polar Scan Matcher by Albert Diosi and Lindsay Kleeman, used for laser scan registration.
-
-
- Ivan Dryanovski
- Ivan Dryanovski
- Carlos
- GPL
-
- http://ros.org/wiki/polar_scan_matcher
-
- catkin
-
- tf
- roscpp
- sensor_msgs
- geometry_msgs
- tf
- roscpp
- sensor_msgs
- geometry_msgs
-
-
-
diff --git a/polar_scan_matcher/src/polar_match.cpp b/polar_scan_matcher/src/polar_match.cpp
deleted file mode 100644
index af58d02..0000000
--- a/polar_scan_matcher/src/polar_match.cpp
+++ /dev/null
@@ -1,876 +0,0 @@
-/***************************************************************************
- polar_match.cpp - matching laser scans in polar coord system
- designed for use with SICK LMS in cm res./361 meas. mode
- only 181 readings (1 deg res) are used (less accuracy but higher
- speed) - changes made to accomodate other lasers, but not tested properly yet.
- -------------------
-begin : Tue Nov 9 2004
-version : 0.2
-copyright : (C) 2005,2006,2007,2008,2009 by Albert Diosi and Lindsay Kleeman
-email : albert.diosi@gmail.com
-comments : - range units are cm; angle units are deg
- - don't forget to set the optimization switch!
- - if it works with float->change fabs-fabsf, floor->floorf
- - why not add angle as well to the iterative least squares?
- => bad convergence, error tends to be fixed with rotation
- - try to make the C - coef for sigmoid function smaller with
- with the as scanmatching converges, to increase the precision
- as in dudek
-changed:
- 05/03/2007- add interpolation to icp
- 04/11/2005- bug fixed in pm_is_corridor. Bug pointed out by Alan Zhang
- 03/08/2005- simple implementation of IDC added not working yet - remove!
- 26/05/2005- projection filter of ICP fixed
- 7/12/2004 - dx,dy estimation interleaved with dth estimation
- seems to work OK
- 3/12/2004 - iterative range least squares seems to work (for
- dx,dy only), though it needs to be thoroughly tested
-
- 26/11/2004
-
-edited: (Ivan Dyanovski, ivan.dryanovski@gmail.com)
-
- 11/08/2010 - removed everything related to visualisation
- - changed defines to private class members
- - removed methods and variables not needed for basic
- matching
-
-
-TODO: change the time measurement approach; do a proper cleanup. have doxygen comments.
- - Comment colours used when GR is defined.
- - Document all magic constansts.(pm_psm: change of C after 10 steps)
-***************************************************************************/
-/****************************************************************************
- This file is part of polar_matching.
-
- polar_matching is free software; you can redistribute it and/or modify
- it under the terms of the GNU General Public License as published by
- the Free Software Foundation; either version 2 of the License, or
- (at your option) any later version.
-
- polar_matching is distributed in the hope that it will be useful,
- but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- GNU General Public License for more details.
-
- You should have received a copy of the GNU General Public License
- along with polar_matching; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
-****************************************************************************/
-
-#include "polar_scan_matcher/polar_match.h"
-
-using namespace std;
-
-PolarMatcher::PolarMatcher()
-{
-
-}
-
-/** @brief Initialises internar variables
-*/
-void PolarMatcher::pm_init()
-{
- pm_fi.resize(PM_L_POINTS);
- pm_si.resize(PM_L_POINTS);
- pm_co.resize(PM_L_POINTS);
-
- PM_FI_MIN = M_PI/2.0 - PM_FOV*PM_D2R/2.0;
- PM_FI_MAX = M_PI/2.0 + PM_FOV*PM_D2R/2.0;
- PM_DFI = PM_FOV*PM_D2R/ ( PM_L_POINTS + 1.0 );
-
- for ( int i=0;i=0 ) ?j:0 );
- r[k]=ls->r[ ( ( l < PM_L_POINTS ) ?l: ( PM_L_POINTS-1 ) ) ];
- k++;
- }
- //bubble sort r
- for ( j= ( WINDOW-1 );j>0;j-- )
- for ( k=0;kr[k+1] ) // wrong order? - swap them
- {
- w=r[k];
- r[k]=r[k+1];
- r[k+1] = w;
- }
- ls->r[i] = r[HALF_WINDOW];//choose the middle point
- }
-}
-
-//-------------------------------------------------------------------------
-// segments scanpoints into groups based on range discontinuities
-// number 0 is reserved to segments with size 1
-// assumptions: too far points PM_MAX_RANGE - divide segments
-// - bad points are only due to far points and mixed pixels
-// seems all right, except a far point can be the beginning of a new segment
-// if the next point is good and close -> it shouldn't make a difference
-void PolarMatcher::pm_segment_scan ( PMScan *ls )
-{
- const PM_TYPE MAX_DIST = 20.0;//max range diff between conseq. points in a seg
- PM_TYPE dr;
- int seg_cnt = 0;
- int i,cnt;
- bool break_seg;
-
- seg_cnt = 1;
-
- //init:
- if ( fabs ( ls->r[0]-ls->r[1] ) seg[0] = seg_cnt;
- ls->seg[1] = seg_cnt;
- cnt = 2; //2 points in the segment
- }
- else
- {
- ls->seg[0] = 0; //point is a segment in itself
- ls->seg[1] = seg_cnt;
- cnt = 1;
- }
-
- for ( i=2;ibad[i] )
- {
- break_seg = true;
- ls->seg[i] = 0;
- }
- else
- {
- dr = ls->r[i]- ( 2.0*ls->r[i-1]-ls->r[i-2] );//extrapolate & calc difference
- if ( fabs ( ls->r[i]-ls->r[i-1] ) seg[i-1]==ls->seg[i-2] )
- && fabs ( dr ) seg[i] = seg_cnt;
- }
- else
- break_seg = true;
- }//if ls
- if ( break_seg ) // breaking the segment?
- {
- if ( cnt==1 )
- {
- //check first if the last three are not on a line by coincidence
- dr = ls->r[i]- ( 2.0*ls->r[i-1]-ls->r[i-2] );
- if ( ls->seg[i-2] == 0 && ls->bad[i] == 0 && ls->bad[i-1] == 0
- && ls->bad[i-2] == 0 && fabs ( dr ) seg[i] = seg_cnt;
- ls->seg[i-1] = seg_cnt;
- ls->seg[i-2] = seg_cnt;
- cnt = 3;
- }//if ls->
- else
- {
- ls->seg[i-1] = 0;
- //what if ls[i] is a bad point? - it could be the start of a new
- //segment if the next point is a good point and is close enough!
- //in that case it doesn't really matters
- ls->seg[i] = seg_cnt;//the current point is a new segment
- cnt = 1;
- }
- }//if cnt ==1
- else
- {
- seg_cnt++;
- ls->seg[i] = seg_cnt;
- cnt = 1;
- }//else if cnt
- }//if break seg
- }//for
-}//pm_segment_scan
-
-//-------------------------------------------------------------------------
-// marks point further than a given distance PM_MAX_RANGE as PM_RANGE
-void PolarMatcher::pm_find_far_points ( PMScan *ls )
-{
- for ( int i=0;ir[i]>PM_MAX_RANGE )
- ls->bad[i] |= PM_RANGE;
- }//
-}
-
-//-------------------------------------------------------------------------
-//calculates an error index expressing the quality of the match
-//of the actual scan to the reference scan
-//has to be called after scan matching so the actual scan in expressed
-//in the reference scan coordinate system
-//return the average minimum Euclidean distance; MAXIMUM RANGE points
-//are not considered; number of non maximum range points have to be
-//smaller than a threshold
-//actual scan is compared to reference scan and vice versa, maximum is
-//taken
-//I could implement it in polar frame as well, would be O(n)
-PM_TYPE PolarMatcher::pm_error_index ( PMScan *lsr,PMScan *lsa )
-{
- int i,j;
- PM_TYPE rx[PM_L_POINTS],ry[PM_L_POINTS],ax[PM_L_POINTS],ay[PM_L_POINTS];
- PM_TYPE x,y;
- PM_TYPE d,dmin,dsum,dx,dy;
- PM_TYPE dsum1;
- int n,n1,rn=0,an=0;
- const PM_TYPE HUGE_ERROR = 1000000;
- const int MIN_POINTS = 100;
-
- lsa->th = norm_a ( lsa->th );
- PM_TYPE co = cos ( lsa->th ),si = sin ( lsa->th );
- PM_TYPE c,sig;
-
- //x axis equation si*x-co*y+c=0
- c = - ( lsa->rx*si-lsa->ry*co );//calc for the x axis of the actual frame
- //"signum" of a point from the lasers view substituted into the equation
- sig = si* ( lsa->rx+cos ( lsa->th+0.1 ) )-co* ( lsa->ry+sin ( lsa->th+0.1 ) ) +c;
-
- for ( i=0;ir[i]*pm_co[i];
- y = lsr->r[i]*pm_si[i];
- if ( !lsr->bad[i] && sig* ( si*x-co*y+c ) >0 )
- {
- rx[rn] = x;
- ry[rn++] = y;
- }//if
- if ( !lsa->bad[i] )
- {
- x = lsa->r[i]*pm_co[i];
- y = lsa->r[i]*pm_si[i];
- ax[an] = x*co-y*si+lsa->rx;
- ay[an] = x*si+y*co+lsa->ry;
- if ( ay[an]>0 )
- {
- an++;
- }
- }//if
- }//for i
-
- dsum = 0;n=0;
- for ( i=0;i0 )
- {
- dsum1 = dsum/ ( PM_TYPE ) n;
- n1 = n;
- }
- else
- return HUGE_ERROR;
-
- //now checking the reference scan agains the actual
- dsum = 0;n=0;
- for ( i=0;i0 )
- {
- dsum = dsum/ ( PM_TYPE ) n;
- }
- else
- return HUGE_ERROR;
-
- cout<<"pm_error_index: "<MIN_POINTS && n>MIN_POINTS )
- {
- if ( dsum1>dsum )
- return dsum1; //return the larger one
- else
- return dsum;
- }
- return HUGE_ERROR;
-}
-
-//-------------------------------------------------------------------------
-//estimates the covariance matrix(c11,c12,c22,c33) (x,y,th) of
-//a scan match based on an error index (err-depends on how good the
-//match is), and the angle of the corridor if it is a corridor
-// for non corridors cov matrix is diagonal
-void PolarMatcher::pm_cov_est ( PM_TYPE err, double *c11,double *c12, double *c22, double *c33,
- bool corridor, PM_TYPE corr_angle )
-{
-#define SQ(x) ((x)*(x))
- const double cov_x = SQ ( 20 ); //10 // cm
- const double cov_y = SQ ( 20 );//10 // cm
- const double cov_th = SQ ( 4.0*M_PI/180.0 ); // 2 deg
- //for corridors
- const double cov_along = SQ ( 400 ); // cm
- const double cov_across = SQ ( 30 ); // cm
-
- err = err-5;
- if ( err<1 )
- err = 1;
- if ( corridor ) //was the actual scan taken of a corridor?
- {
- double co = cos ( corr_angle );
- double si = sin ( corr_angle );
- *c11 = err* ( SQ ( co ) *cov_along+SQ ( si ) *cov_across );
- *c12 = err* ( -co*si* ( -cov_along+cov_across ) );
- *c22 = err* ( SQ ( si ) *cov_along+SQ ( co ) *cov_across );
- *c33 = err*cov_th;
- }//if
- else
- {
- *c12 = 0;
- *c11 = err*cov_x;
- *c22 = err*cov_y;
- *c33 = err*cov_th;
- }//else
-}//pm_cov_est
-
-//-------------------------------------------------------------------------
-// does scan matching using the equations for translation and orietation
-//estimation as in Lu & milios, however our matching bearing association rule
-//is used together with our association filter.
-//have to do an angle search othervise doesn't converge to 0!
-//weights implemented!
-PM_TYPE PolarMatcher::pm_psm_c ( PMScan *lsr,PMScan *lsa )
-{
-// #define GR //comment out if no graphics necessary
- PMScan act(PM_L_POINTS), ref(PM_L_POINTS);//copies of actual and reference scans
- PM_TYPE rx,ry,rth,ax,ay,ath;//robot pos at ref and actual scans
- PM_TYPE t13,t23;
- PM_TYPE new_r[PM_L_POINTS];//interpolated r at measurement bearings
- int new_bad[PM_L_POINTS];//bad flags of the interpolated range readings
- PM_TYPE C = 70*70;//weighting factor; see dudek00
- int n = 0;//number of valid points
- int iter,i,small_corr_cnt=0;
- PM_TYPE abs_err=0,dx=0,dy=0,dth=0;//match error, actual scan corrections
-
- act = *lsa;
- ref = *lsr;
-
- rx = ref.rx; ry = ref.ry; rth = ref.th;
- ax = act.rx; ay = act.ry; ath = act.th;
-
- //transformation of actual scan laser scanner coordinates into reference
- //laser scanner coordinates
- t13 = cos(rth) * ax + sin(rth) * ay - sin (rth) * ry - rx * cos(rth);
- t23 = -sin(rth) * ax + cos(rth) * ay - cos (rth) * ry + rx * sin(rth);
-
- ref.rx = 0; ref.ry = 0; ref.th = 0;
- act.rx = t13; act.ry = t23; act.th = ath-rth;
-
- ax = act.rx; ay = act.ry; ath = act.th;
- //from now on act.rx,.. express the lasers position in the ref frame
-
- iter = -1;
- while ( ++iter10 )
- C = 100;
-
- // do the weighted linear regression on the linearized ...
- // include angle as well
- PM_TYPE dr;
-
- //computation of the new dx1,dy1,dtheta1
- PM_TYPE X=0,Y=0,Xp=0,Yp=0,W=0,w;
- PM_TYPE sxx=0,sxy=0,syx=0, syy=0;
- PM_TYPE meanpx,meanpy,meanppx,meanppy;
- meanpx = 0;meanpy = 0;
- meanppx= 0;meanppy= 0;
-
- abs_err=0;
- n=0;
- for ( i=0;i10.0 && fabs ( dr ) rx =ax;lsa->ry=ay;lsa->th=ath;
- return ( abs_err/n );
-}//pm_psm_c
-
-//-------------------------------------------------------------------------
-// minimizes least square error through changing lsa->rx, lsa->ry,lsa->th
-// this looks for angle too, like pm_linearized_match_proper,execept it
-// fits a parabola to the error when searching for the angle and interpolates.
-PM_TYPE PolarMatcher::pm_psm ( PMScan *lsr,PMScan *lsa )
-{
- PMScan act(PM_L_POINTS), ref(PM_L_POINTS);//copies of actual and reference scans
- PM_TYPE rx,ry,rth,ax,ay,ath;//robot pos at ref and actual scans
- PM_TYPE t13,t23;
- PM_TYPE new_r[PM_L_POINTS];//interpolated r at measurement bearings
- int new_bad[PM_L_POINTS];//bad flags of the interpolated range readings
- PM_TYPE C = 70*70;//weighting factor; see dudek00
- int iter,small_corr_cnt=0;
- PM_TYPE dx=0,dy=0,dth=0;//match error, actual scan corrections
- PM_TYPE avg_err = 100000000.0;
-
- act = *lsa;
- ref = *lsr;
-
- rx = ref.rx; ry = ref.ry; rth = ref.th;
- ax = act.rx; ay = act.ry; ath = act.th;
-
- //transformation of actual scan laser scanner coordinates into reference
- //laser scanner coordinates
- t13 = cos(rth) * ax + sin(rth) * ay-sin (rth) * ry - rx * cos (rth);
- t23 = -sin(rth) * ax + cos(rth) * ay-cos (rth) * ry + rx * sin (rth);
-
- ref.rx = 0; ref.ry = 0; ref.th = 0;
- act.rx = t13; act.ry = t23; act.th = ath-rth;
-
- ax = act.rx; ay = act.ry; ath = act.th;
- //from now on act.rx,.. express the lasers position in the ref frame
-
- iter = -1;
- while ( ++iter10 )
- C = 100;
-
- avg_err = pm_translation_estimation(&ref, new_r, new_bad, C, &dx, &dy);
-
- ax += dx;
- ay += dy;
-
-// //for SIMULATION iteration results..
-
- }//while iter
-
- lsa->rx =ax;lsa->ry=ay;lsa->th=ath;
- return ( avg_err);
-}//pm_linearized_match_int_angle
-
-//-------------------------------------------------------------------------
-//calculate distance of the point (x3,y3) from a line (defined by (x1,y1)
-//and (x2,y2)). Returns the distance to the line or -1 if the
-//projection of (x3,y3) falls outside the line segment defined by (x1,y1)
-//and (x2,y2).
-//The projection of (x3,y3) onto the line is also returned in x,y
-PM_TYPE PolarMatcher::point_line_distance ( PM_TYPE x1, PM_TYPE y1, PM_TYPE x2, PM_TYPE y2,
- PM_TYPE x3, PM_TYPE y3,PM_TYPE *x, PM_TYPE *y )
-{
- PM_TYPE ax,ay,t1,D;
- ax = x2-x1;
- ay = y2-y1;
- D = sqrt ( ax*ax+ay*ay );
- if ( D <0.0001 )
- {
- cerr <<"point_line_distance: unexpected D:" <1 ) // projection falls outside the line segment
- {
- return -1;
- }
- *x = x1+t1*ax;
- *y = y1+t1*ay;
- return ( sqrt ( ( x3-*x ) * ( x3-*x ) + ( y3-*y ) * ( y3-*y ) ) );//distance of line to p.
-}// point_line_distance
-
-//-------------------------------------------------------------------------
-//! projects the current (active) scan act to the base (ref.) (0,0,0) coordinate frame
-//! returns in new_r interpolated r at measurement bearings
-//! returns in new_bad bad flags of the interpolated range readings
-void PolarMatcher::pm_scan_project(const PMScan *act, PM_TYPE *new_r, int *new_bad)
-{
- PM_TYPE r[PM_L_POINTS],fi[PM_L_POINTS];//actual scan in ref. coord. syst.
- PM_TYPE x,y;
- int i;
- PM_TYPE delta;
-
- // convert range readings into ref frame
- // this can be speeded up, by connecting it with the interpolation
- for ( i=0;ith + pm_fi[i];
- x = act->r[i]*cos ( delta ) + act->rx;
- y = act->r[i]*sin ( delta ) + act->ry;
- r[i] = sqrt ( x*x+y*y );
- fi[i] = atan2 ( y,x );
- //handle discontinuity at pi
- if(x<0 && y<0)
- fi[i] += 2.0*M_PI;
-
- new_r[i] = 10000;//initialize big interpolated r;
- new_bad[i]= PM_EMPTY;//for interpolated r;
-
- }//for i
-
- //------------------------INTERPOLATION------------------------
- //calculate/interpolate the associations to the ref scan points
- //algorithm ignores crosings at 0 and 180 -> to make it faster
- for ( i=1;iseg[i] != 0 && act->seg[i] == act->seg[i-1] && !act->bad[i] &&
- !act->bad[i-1] /* && fi[i]>PM_FI_MIN && fi[i-1]>PM_FI_MIN*/ )
- {
- //calculation of the "whole" parts of the angles
- int j0,j1;
- PM_TYPE r0,r1,a0,a1;
- bool occluded;
- if ( fi[i]>fi[i-1] ) //are the points visible?
- {
- //visible
- occluded = false;
- a0 = fi[i-1];
- a1 = fi[i];
-
- j0 = (int) ceil ( ( fi[i-1] - PM_FI_MIN ) /PM_DFI );
- j1 = (int) floor ( ( fi[i] - PM_FI_MIN ) /PM_DFI );
- r0 = r[i-1];
- r1 = r[i];
- }
- else
- {
- //invisible - still have to calculate to filter out points which
- occluded = true; //are covered up by these!
- //flip the points-> easier to program
- a0 = fi[i];
- a1 = fi[i-1];
-
- j0 = (int) ceil ( ( fi[i] - PM_FI_MIN ) /PM_DFI );
- j1 = (int) floor ( ( fi[i-1] - PM_FI_MIN ) /PM_DFI );
- r0 = r[i];
- r1 = r[i-1];
- }
- //here fi0 is always smaller than fi1!
-
- //interpolate for all the measurement bearings beween fi0 and fi1
- while ( j0<=j1 ) //if at least one measurement point difference, then ...
- {
- // cout <<( ( PM_TYPE ) j0*PM_DFI )<<" "<<( ( ( PM_TYPE ) j0*PM_DFI +PM_FI_MIN )-a0 )< falls into the measurement range and ri is shorter
- //than the current range then overwrite it
- if ( j0>=0 && j0ri )
- {
- new_r[j0] = ri;//overwrite the previous reading
- new_bad[j0] &=~PM_EMPTY;//clear the empty flag
- if ( occluded ) //check if it was occluded
- new_bad[j0] = new_bad[j0]|PM_OCCLUDED;//set the occluded flag
- else
- new_bad[j0] = new_bad[j0]&~PM_OCCLUDED;
- //the new range reading also it has to inherit the other flags
- new_bad[j0] |= act->bad[i];//superfluos - since act.bad[i] was checked for 0
- new_bad[j0] |= act->bad[i-1];//superfluos - since act.bad[i-1] was checked for 0
-
- }
- j0++;//check the next measurement angle!
- }//while
- }//if act
- }//for i
-}//pm_scan_project
-
-//-------------------------------------------------------------------------
-//! Function estimating the orientation of the current scan represented with range readings
-//! new_r and flags new_bad with respect to the reference scan ref.
-//! Assuming that the current and ref scan were taken at the same position, to an orientation
-//! change of the current scan a left or right shift of the scan ranges corresponds.
-//! The functions estimates the orientation by finding that shift which minimizes the
-//! difference between the current and ref. scan. The orientation estimate is then
-//! refined using interpolation.
-PM_TYPE PolarMatcher::pm_orientation_search(const PMScan *ref, const PM_TYPE *new_r, const int *new_bad)
-{
- int i;
- int window = PM_SEARCH_WINDOW;//20;//+- width of search for correct orientation
- PM_TYPE dth=0;//\actual scan corrections
-
- //pm_fi,ref.r - reference points
- PM_TYPE e,err[PM_L_POINTS]; // the error rating
- PM_TYPE beta[PM_L_POINTS];// angle for the corresponding error
- PM_TYPE n;
- int k=0;
-
- for ( int di=-window;di<=window;di++ )
- {
- n=0;e=0;
-
- int min_i,max_i;
- if ( di<=0 )
- {min_i = -di;max_i=PM_L_POINTS;}
- else
- {min_i = 0;max_i=PM_L_POINTS-di;}
-
- for ( i=min_i;ibad[i+di] )
- {
- e += fabs ( new_r[i]-ref->r[i+di] );
- n++;
- }
-
- }//for i
-
- if ( n>0 )
- err[k] = e/n;//don't forget to correct with n!
- else
- err[k] = 10000;//don't forget to correct with n!
- beta[k] = di;
- k++;
- }//for dfi
-
- //now search for the global minimum
- //later I can make it more robust
- //assumption: monomodal error function!
- PM_TYPE emin = 1000000;
- int imin;
- for ( i=0;i=10000 )
- {
- cerr <<"Polar Match: orientation search failed" <=1 && imin< ( k-1 ) ) //is it not on the extreme?
- {
- //lets try interpolation
- PM_TYPE D = err[imin-1]+err[imin+1]-2.0*err[imin];
- PM_TYPE d=1000;
- if ( fabs ( D ) >0.01 && err[imin-1]>err[imin] && err[imin+1]>err[imin] )
- d= ( err[imin-1]-err[imin+1] ) /D/2.0;
-
- if ( fabs ( d ) <1 )
- dth+=d*PM_DFI;
- }//if
-
- return(dth);
-}//pm_orientation_search
-
-PM_TYPE PolarMatcher::pm_translation_estimation(const PMScan *ref, const PM_TYPE *new_r, const int *new_bad, PM_TYPE C, PM_TYPE *dx, PM_TYPE *dy)
-{
- // do the weighted linear regression on the linearized ...
- // include angle as well
- int i;
- PM_TYPE hi1, hi2,hwi1,hwi2, hw1=0,hw2=0,hwh11=0;
- PM_TYPE hwh12=0,hwh21=0,hwh22=0,w;
- PM_TYPE dr;
- PM_TYPE abs_err = 0;
- int n = 0;
- for ( i=0;ir[i]-new_r[i];
- abs_err += fabs ( dr );
-
- //weight calculation
- if (ref->bad[i] == 0 &&
- new_bad[i] == 0 &&
- new_r[i] < PM_MAX_RANGE &&
- new_r[i] > 10.0 &&
- fabs(dr) < PM_MAX_ERROR )
- {
- //weighting according to DUDEK00
-
- w = C / (dr*dr + C);
- n++;
-
- //proper calculations of the jacobian
- hi1 = pm_co[i];//xx/new_r[i];//this the correct
- hi2 = pm_si[i];//yy/new_r[i];
-
- hwi1 = hi1*w;
- hwi2 = hi2*w;
-
- //par = (H^t*W*H)^-1*H^t*W*dr
- hw1 += hwi1*dr;//H^t*W*dr
- hw2 += hwi2*dr;
-
- //H^t*W*H
- hwh11 += hwi1*hi1;
- hwh12 += hwi1*hi2;
- hwh21 += hwi2*hi1; //should take adv. of symmetricity!!
- hwh22 += hwi2*hi2;
- }
- else
- {
-/*
- if (ref->bad[i] != 0) printf("rb ");
- if (new_bad[i] != 0) printf("nb ");
- if (new_r[i] < PM_MAX_RANGE) printf("MR ");
- if (fabs(dr) < PM_MAX_ERROR) printf("ME ");
- printf(".\n");
- */
- }
- }//for i
- if ( n
-* William Morris
-* http://robotics.ccny.cuny.edu
-* Modified 2014, Daniel Axtens
-* whilst a student at the Australian National University
-*
-* This program is free software: you can redistribute it and/or modify
-* it under the terms of the GNU General Public License as published by
-* the Free Software Foundation, either version 3 of the License, or
-* (at your option) any later version.
-*
-* This program is distributed in the hope that it will be useful,
-* but WITHOUT ANY WARRANTY; without even the implied warranty of
-* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-* GNU General Public License for more details.
-*
-* You should have received a copy of the GNU General Public License
-* along with this program. If not, see .
-*
-* This is a wrapper around Polar Scan Matcher [1], written by
-* Albert Diosi
-*
-* [1] A. Diosi and L. Kleeman, "Laser Scan Matching in Polar Coordinates with
-* Application to SLAM " Proceedings of 2005 IEEE/RSJ International Conference
-* on Intelligent Robots and Systems, August, 2005, Edmonton, Canada
-*/
-
-#include "polar_scan_matcher/psm_node.h"
-
-int main (int argc, char** argv)
-{
- ros::init(argc, argv, "PolarScanMatching Node");
- PSMNode psmNode;
- ros::spin();
-}
-
-PSMNode::PSMNode()
-{
- ROS_INFO("Creating PolarScanMatching node");
-
- ros::NodeHandle nh;
-
- initialized_ = false;
- totalDuration_ = 0.0;
- scansCount_ = 0;
-
- prevWorldToBase_.setIdentity();
-
- getParams();
-
- scanSubscriber_ = nh.subscribe (scanTopic_, 10, &PSMNode::scanCallback, this);
- imuSubscriber_ = nh.subscribe (imuTopic_, 10, &PSMNode::imuCallback, this);
- posePublisher_ = nh.advertise(poseTopic_, 10);
-}
-
-PSMNode::~PSMNode()
-{
- ROS_INFO("Destroying PolarScanMatching node");
-}
-
-void PSMNode::getParams()
-{
- ros::NodeHandle nh_private("~");
-
- std::string odometryType;
-
- // **** wrapper parameters
-
- if (!nh_private.getParam ("world_frame", worldFrame_))
- worldFrame_ = "world";
- if (!nh_private.getParam ("base_frame", baseFrame_))
- baseFrame_ = "base_link";
- if (!nh_private.getParam ("publish_tf", publishTf_))
- publishTf_ = true;
- if (!nh_private.getParam ("publish_pose", publishPose_))
- publishPose_ = true;
- if (!nh_private.getParam ("odometry_type", odometryType))
- odometryType = "none";
-
- if (odometryType.compare("none") == 0)
- {
- useTfOdometry_ = false;
- useImuOdometry_ = false;
- }
- else if (odometryType.compare("tf") == 0)
- {
- useTfOdometry_ = true;
- useImuOdometry_ = false;
- }
- else if (odometryType.compare("imu") == 0)
- {
- useTfOdometry_ = false;
- useImuOdometry_ = true;
- }
- else
- {
- ROS_WARN("Unknown value of odometry_type parameter passed to psm_node. \
- Using default value (\"none\")");
- useTfOdometry_ = false;
- useImuOdometry_ = false;
- }
-
- // **** PSM parameters
-
- if (!nh_private.getParam ("min_valid_points", minValidPoints_))
- minValidPoints_ = 200;
- if (!nh_private.getParam ("search_window", searchWindow_))
- searchWindow_ = 40;
- if (!nh_private.getParam ("max_error", maxError_))
- maxError_ = 0.20;
- if (!nh_private.getParam ("max_iterations", maxIterations_))
- maxIterations_ = 20;
- if (!nh_private.getParam ("stop_condition", stopCondition_))
- stopCondition_ = 0.01;
-}
-
-bool PSMNode::initialize(const sensor_msgs::LaserScan& scan)
-{
- laserFrame_ = scan.header.frame_id;
-
- // **** get base to laser tf
-
- tf::StampedTransform baseToLaserTf;
- try
- {
- tfListener_.waitForTransform(baseFrame_, scan.header.frame_id, scan.header.stamp, ros::Duration(1.0));
- tfListener_.lookupTransform (baseFrame_, scan.header.frame_id, scan.header.stamp, baseToLaserTf);
- }
- catch (tf::TransformException ex)
- {
- ROS_WARN("ScanMatcherNode: Could get initial laser transform, skipping scan (%s)", ex.what());
- return false;
- }
- baseToLaser_ = baseToLaserTf;
- laserToBase_ = baseToLaser_.inverse();
-
- // **** pass parameters to matcher and initialise
-
- matcher_.PM_L_POINTS = scan.ranges.size();
-
- matcher_.PM_FOV = (scan.angle_max - scan.angle_min) * 180.0 / M_PI;
- matcher_.PM_MAX_RANGE = scan.range_max * ROS_TO_PM;
-
- matcher_.PM_TIME_DELAY = 0.00;
-
- matcher_.PM_MIN_VALID_POINTS = minValidPoints_;
- matcher_.PM_SEARCH_WINDOW = searchWindow_;
- matcher_.PM_MAX_ERROR = maxError_ * ROS_TO_PM;
-
- matcher_.PM_MAX_ITER = maxIterations_;
- matcher_.PM_MAX_ITER_ICP = maxIterations_;
- matcher_.PM_STOP_COND = stopCondition_ * ROS_TO_PM;
- matcher_.PM_STOP_COND_ICP = stopCondition_ * ROS_TO_PM;
-
- matcher_.pm_init();
-
- // **** get the initial worldToBase tf
-
- getCurrentEstimatedPose(prevWorldToBase_, scan);
-
- // **** create the first pm scan from the laser scan message
-
- tf::Transform t;
- t.setIdentity();
- prevPMScan_ = new PMScan(scan.ranges.size());
- rosToPMScan(scan, t, prevPMScan_);
-
- return true;
-}
-
-void PSMNode::imuCallback (const sensor_msgs::Imu& imuMsg)
-{
- imuMutex_.lock();
- tf::Quaternion q(imuMsg.orientation.x, imuMsg.orientation.y, imuMsg.orientation.z, imuMsg.orientation.w);
- tf::Matrix3x3 m(q);
- double temp;
- m.getRPY(temp, temp, currImuAngle_);
- imuMutex_.unlock();
-}
-
-void PSMNode::scanCallback(const sensor_msgs::LaserScan& scan)
-{
- ROS_DEBUG("Received scan");
- scansCount_++;
-
- struct timeval start, end;
- gettimeofday(&start, NULL);
-
- // **** if this is the first scan, initialize and leave the function here
-
- if (!initialized_)
- {
- initialized_ = initialize(scan);
- if (initialized_) ROS_INFO("Matcher initialized");
- return;
- }
-
- // **** attmempt to match the two scans
-
- // PM scan matcher is used in the following way:
- // The reference scan (prevPMScan_) always has a pose of 0
- // The new scan (currPMScan) has a pose equal to the movement
- // of the laser in the world frame since the last scan (tf::Transform change)
- // The computed correction is then propagated using the tf machinery
-
- prevPMScan_->rx = 0;
- prevPMScan_->ry = 0;
- prevPMScan_->th = 0;
-
- tf::Transform currWorldToBase;
- tf::Transform change;
- change.setIdentity();
-
- // what odometry model to use
- if (useTfOdometry_)
- {
- // get the current position of the base in the world frame
- // if no transofrm is available, we'll use the last known transform
-
- getCurrentEstimatedPose(currWorldToBase, scan);
- change = laserToBase_ * prevWorldToBase_.inverse() * currWorldToBase * baseToLaser_;
- }
- else if (useImuOdometry_)
- {
- imuMutex_.lock();
- double dTheta = currImuAngle_ - prevImuAngle_;
- prevImuAngle_ = currImuAngle_;
- change.getRotation().setRPY(0.0, 0.0, dTheta);
- imuMutex_.unlock();
- }
-
- PMScan * currPMScan = new PMScan(scan.ranges.size());
- rosToPMScan(scan, change, currPMScan);
-
- try
- {
- matcher_.pm_psm(prevPMScan_, currPMScan);
- }
- catch(int err)
- {
- ROS_WARN("Error in scan matching");
- delete prevPMScan_;
- prevPMScan_ = currPMScan;
- return;
- };
-
- // **** calculate change in position
-
- // rotate by -90 degrees, since polar scan matcher assumes different laser frame
- // and scale down by 100
- double dx = currPMScan->ry / ROS_TO_PM;
- double dy = -currPMScan->rx / ROS_TO_PM;
- double da = currPMScan->th;
-
- // change = scan match result for how much laser moved between scans,
- // in the world frame
- change.setOrigin(tf::Vector3(dx, dy, 0.0));
- tf::Quaternion q;
- q.setRPY(0, 0, da);
- change.setRotation(q);
-
- // **** publish the new estimated pose as a tf
-
- currWorldToBase = prevWorldToBase_ * baseToLaser_ * change * laserToBase_;
-
- if (publishTf_ ) publishTf (currWorldToBase, scan.header.stamp);
- if (publishPose_) publishPose(currWorldToBase);
-
- // **** swap old and new
-
- delete prevPMScan_;
- prevPMScan_ = currPMScan;
- prevWorldToBase_ = currWorldToBase;
-
- // **** timing information - needed for profiling only
-
- gettimeofday(&end, NULL);
- double dur = ((end.tv_sec * 1000000 + end.tv_usec ) -
- (start.tv_sec * 1000000 + start.tv_usec)) / 1000.0;
- totalDuration_ += dur;
- double ave = totalDuration_/scansCount_;
-
- ROS_INFO("dur:\t %.3f ms \t ave:\t %.3f ms", dur, ave);
-}
-
-void PSMNode::publishTf(const tf::Transform& transform,
- const ros::Time& time)
-{
- tf::StampedTransform transformMsg (transform, time, worldFrame_, baseFrame_);
- tfBroadcaster_.sendTransform (transformMsg);
-}
-
-void PSMNode::publishPose(const tf::Transform& transform)
-{
- geometry_msgs::Pose2D pose;
- tfToPose2D(transform, pose);
-
- posePublisher_.publish(pose);
-}
-
-void PSMNode::rosToPMScan(const sensor_msgs::LaserScan& scan,
- const tf::Transform& change,
- PMScan* pmScan)
-{
- geometry_msgs::Pose2D pose;
- tfToPose2D(change, pose);
-
- // FIXME: rotate x & y by 90 degree?
-
- pmScan->rx = pose.x * ROS_TO_PM;
- pmScan->ry = pose.y * ROS_TO_PM;
- pmScan->th = pose.theta;
-
- for (int i = 0; i < scan.ranges.size(); ++i)
- {
- if (scan.ranges[i] == 0)
- {
- pmScan->r[i] = 99999; // hokuyo uses 0 for out of range reading
- }
- else
- {
- pmScan->r[i] = scan.ranges[i] * ROS_TO_PM;
- pmScan->x[i] = (pmScan->r[i]) * matcher_.pm_co[i];
- pmScan->y[i] = (pmScan->r[i]) * matcher_.pm_si[i];
- pmScan->bad[i] = 0;
- }
-
- pmScan->bad[i] = 0;
- }
-
- matcher_.pm_median_filter (pmScan);
- matcher_.pm_find_far_points(pmScan);
- matcher_.pm_segment_scan (pmScan);
-}
-
-void PSMNode::getCurrentEstimatedPose(tf::Transform& worldToBase,
- const sensor_msgs::LaserScan& scanMsg)
-{
- tf::StampedTransform worldToBaseTf;
- try
- {
- tfListener_.lookupTransform (worldFrame_, baseFrame_, scanMsg.header.stamp, worldToBaseTf);
- }
- catch (tf::TransformException ex)
- {
- // transform unavailable - use the pose from our last estimation
- ROS_WARN("Transform unavailable, using last estimated pose (%s)", ex.what());
- worldToBase = prevWorldToBase_;
- return;
- }
- worldToBase = worldToBaseTf;
-}
-
-void PSMNode::pose2DToTf(const geometry_msgs::Pose2D& pose, tf::Transform& t)
-{
- t.setOrigin(tf::Vector3(pose.x, pose.y, 0.0));
- tf::Quaternion q;
- q.setRPY(0, 0, pose.theta);
- t.setRotation(q);
-}
-
-void PSMNode::tfToPose2D(const tf::Transform& t, geometry_msgs::Pose2D& pose)
-{
- tf::Matrix3x3 m(t.getRotation());
- double roll, pitch, yaw;
- m.getRPY(roll, pitch, yaw);
-
- pose.x = t.getOrigin().getX();
- pose.y = t.getOrigin().getY();
- pose.theta = yaw;
-}
diff --git a/scan_to_cloud_converter/CMakeLists.txt b/scan_to_cloud_converter/CMakeLists.txt
index 6fa18ce..6c08271 100644
--- a/scan_to_cloud_converter/CMakeLists.txt
+++ b/scan_to_cloud_converter/CMakeLists.txt
@@ -1,34 +1,25 @@
-cmake_minimum_required(VERSION 2.8.3)
-project(scan_to_cloud_converter)
-
-
-# List C++ dependencies on ros packages
-set( ROS_CXX_DEPENDENCIES
- roscpp
- pcl_ros
- pcl_conversions)
-
-# Find catkin and all required ROS components
-find_package(catkin REQUIRED COMPONENTS ${ROS_CXX_DEPENDENCIES})
-find_package(PCL REQUIRED QUIET)
-
-# Set include directories
-include_directories(include ${catkin_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
-
-# Declare info that other packages need to import library generated here
-catkin_package( )
-
-#Create node
-add_executable( scan_to_cloud_converter_node
- src/scan_to_cloud_converter_node.cpp
- src/scan_to_cloud_converter.cpp )
-
-# No need to link against pcl (using header only libraries)
-target_link_libraries( scan_to_cloud_converter_node ${catkin_LIBRARIES})
-
-add_dependencies(scan_to_cloud_converter_node ${catkin_EXPORTED_TARGETS})
+cmake_minimum_required(VERSION 3.5)
+project(scan_to_cloud_converter)
-#Install node
-install(TARGETS scan_to_cloud_converter_node
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} )
+find_package(ament_cmake REQUIRED)
+find_package(laser_geometry REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(sensor_msgs REQUIRED)
+find_package(tf2 REQUIRED)
+
+add_executable(${PROJECT_NAME} src/scan_to_cloud_converter.cpp)
+target_include_directories(${PROJECT_NAME}
+ PRIVATE
+ "include"
+)
+ament_target_dependencies(${PROJECT_NAME}
+ laser_geometry
+ rclcpp
+ sensor_msgs
+ tf2
+)
+
+install(TARGETS ${PROJECT_NAME} DESTINATION lib/${PROJECT_NAME})
+
+ament_package()
diff --git a/scan_to_cloud_converter/include/scan_to_cloud_converter/scan_to_cloud_converter.h b/scan_to_cloud_converter/include/scan_to_cloud_converter/scan_to_cloud_converter.h
index 436ee37..5d8c7f2 100644
--- a/scan_to_cloud_converter/include/scan_to_cloud_converter/scan_to_cloud_converter.h
+++ b/scan_to_cloud_converter/include/scan_to_cloud_converter/scan_to_cloud_converter.h
@@ -30,36 +30,26 @@
#ifndef SCAN_TO_CLOUD_CONVERTER_SCAN_TO_CLOUD_CONVERTER_H
#define SCAN_TO_CLOUD_CONVERTER_SCAN_TO_CLOUD_CONVERTER_H
-#include
-#include
-#include
-#include
-#include
-#include
+#include
+#include
+#include
+#include
namespace scan_tools {
-class ScanToCloudConverter
-{
- typedef pcl::PointXYZ PointT;
- typedef pcl::PointCloud PointCloudT;
+class ScanToCloudConverter : public rclcpp::Node {
+ public:
- private:
-
- ros::NodeHandle nh_;
- ros::NodeHandle nh_private_;
+ ScanToCloudConverter();
+ ~ScanToCloudConverter() = default;
- ros::Publisher cloud_publisher_;
- ros::Subscriber scan_subscriber_;
-
- PointT invalid_point_;
+ private:
+ rclcpp::Publisher::SharedPtr cloud_pub_;
+ rclcpp::Subscription::SharedPtr scan_sub_;
- void scanCallback(const sensor_msgs::LaserScan::ConstPtr& scan_msg);
-
- public:
+ laser_geometry::LaserProjection laser_projector_;
- ScanToCloudConverter(ros::NodeHandle nh, ros::NodeHandle nh_private);
- ~ScanToCloudConverter();
+ void scanCallback(const sensor_msgs::msg::LaserScan::SharedPtr scan_msg);
};
} // namespace scan_tools
diff --git a/scan_to_cloud_converter/package.xml b/scan_to_cloud_converter/package.xml
index 0604502..62b27c3 100644
--- a/scan_to_cloud_converter/package.xml
+++ b/scan_to_cloud_converter/package.xml
@@ -1,4 +1,6 @@
-
+
+
+scan_to_cloud_converter0.3.3
@@ -13,18 +15,18 @@
BSD
- catkin
+ ament_cmake
- roscpp
- pcl_ros
- pcl_conversions
+ laser_geometry
+ rclcpp
+ sensor_msgs
+ tf2
- libpcl-all-dev
+ ament_lint_auto
+ ament_lint_common
- roscpp
- pcl_ros
- pcl_conversions
-
- libpcl-all
+
+ ament_cmake
+
diff --git a/scan_to_cloud_converter/src/scan_to_cloud_converter.cpp b/scan_to_cloud_converter/src/scan_to_cloud_converter.cpp
index 749c9dd..fac325c 100644
--- a/scan_to_cloud_converter/src/scan_to_cloud_converter.cpp
+++ b/scan_to_cloud_converter/src/scan_to_cloud_converter.cpp
@@ -27,62 +27,32 @@
* POSSIBILITY OF SUCH DAMAGE.
*/
-#include "scan_to_cloud_converter/scan_to_cloud_converter.h"
-
-#include
+#include
namespace scan_tools {
-ScanToCloudConverter::ScanToCloudConverter(ros::NodeHandle nh, ros::NodeHandle nh_private):
- nh_(nh),
- nh_private_(nh_private)
-{
- ROS_INFO("Starting ScanToCloudConverter");
-
- invalid_point_.x = std::numeric_limits::quiet_NaN();
- invalid_point_.y = std::numeric_limits::quiet_NaN();
- invalid_point_.z = std::numeric_limits::quiet_NaN();
+ScanToCloudConverter::ScanToCloudConverter() : rclcpp::Node("scan_to_cloud_converter") {
+ cloud_pub_ = create_publisher("cloud", rclcpp::SystemDefaultsQoS());
- cloud_publisher_ = nh_.advertise