diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index ad729a4f..a5ae207d 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -28,7 +28,7 @@ repos: # Standard hooks - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.6.0 + rev: v5.0.0 hooks: - id: check-added-large-files args: ["--maxkb=2000"] @@ -48,7 +48,7 @@ repos: # Python hooks - repo: https://github.com/asottile/pyupgrade - rev: v3.16.0 + rev: v3.19.1 hooks: - id: pyupgrade args: [--py36-plus] @@ -62,20 +62,20 @@ repos: ["--ignore=D100,D101,D102,D103,D104,D105,D106,D107,D203,D212,D404"] - repo: https://github.com/psf/black - rev: 24.4.2 + rev: 24.10.0 hooks: - id: black args: ["--line-length=99", "--exclude=tools/code_check"] - repo: https://github.com/pycqa/flake8 - rev: 7.1.0 + rev: 7.1.1 hooks: - id: flake8 args: ["--extend-ignore=E501", "--exclude=tools/code_check"] # CPP hooks - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v18.1.7 + rev: v19.1.6 hooks: - id: clang-format args: ["-fallback-style=none", "-i"] @@ -125,7 +125,7 @@ repos: # Docs - RestructuredText hooks - repo: https://github.com/PyCQA/doc8 - rev: v1.1.1 + rev: v1.1.2 hooks: - id: doc8 args: ["--max-line-length=100", "--ignore=D001"] @@ -150,7 +150,7 @@ repos: # Json lint - repo: https://github.com/python-jsonschema/check-jsonschema - rev: 0.28.6 + rev: 0.31.0 hooks: - id: check-github-workflows args: ["--verbose"] @@ -161,7 +161,7 @@ repos: # XML lint for xacro, urdf, and sdf files - repo: https://github.com/pamoller/xmlformatter - rev: v0.2.6 + rev: v0.2.8 hooks: - id: xml-formatter name: Format XML diff --git a/gazebo/dave_gz_multibeam_sonar/README.md b/gazebo/dave_gz_multibeam_sonar/README.md new file mode 100644 index 00000000..2aec05b7 --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/README.md @@ -0,0 +1,18 @@ +# Dave Gazebo Multibeam Sonar Plugin + +- The sensor itself is at `multibeam_sonar` +- The system plugin that will also be defined in `world` file is at `multibeam_sonar_system` +- We need both the sensor and the system plugin to be able to use the sensor in Gazebo + +- Launch example with `dave_sensor.launch.py`: + + ``` + ros2 launch dave_demos dave_sensor.launch.py namespace:=blueview_p900 world_name:=dave_multibeam_sonar paused:=false x:=4 z:=0.5 yaw:=3.14 + ``` + +- Launch example with `ros_gz_bridge` to translate gazebo msg to ROS msg: + - Not perfect + + ``` + ros2 launch dave_multibeam_sonar_demo multibeam_sonar_demo.launch.py + ``` \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/CMakeLists.txt b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/CMakeLists.txt new file mode 100644 index 00000000..17c77311 --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/CMakeLists.txt @@ -0,0 +1,132 @@ +cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) +cmake_policy(SET CMP0144 NEW) + +project(multibeam_sonar) + +find_package(ament_cmake REQUIRED) +find_package(gz-cmake3 REQUIRED) +find_package(gz-sim8 REQUIRED) +find_package(gz-sensors8 REQUIRED) +find_package(gz-rendering8 REQUIRED OPTIONAL_COMPONENTS ogre ogre2) +find_package(gz-transport13 REQUIRED) +find_package(rclcpp REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(rosidl_default_generators REQUIRED) +find_package(PCL REQUIRED) +find_package(pcl_conversions REQUIRED) + +find_package(OpenCV REQUIRED) + +include_directories(${PCL_INCLUDE_DIRS}) +link_directories(${PCL_LIBRARY_DIRS}) +add_definitions(${PCL_DEFINITIONS}) + +# Set version variables +set(GZ_MSGS_VER ${gz-msgs10_VERSION_MAJOR}) +set(GZ_RENDERING_VER ${gz-rendering8_VERSION_MAJOR}) +set(GZ_SENSORS_VER ${gz-sensors8_VERSION_MAJOR}) +set(GZ_TRANSPORT_VER ${gz-transport13_VERSION_MAJOR}) +set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR}) + +if(TARGET gz-rendering${GZ_RENDERING_VER}::ogre) + set(HAVE_OGRE TRUE) + set(GZ_RENDERING_TARGET gz-rendering${GZ_RENDERING_VER}-ogre) + add_definitions(-DWITH_OGRE) +endif() + +if(TARGET gz-rendering${GZ_RENDERING_VER}::ogre2) + set(HAVE_OGRE2 TRUE) + set(GZ_RENDERING_TARGET gz-rendering${GZ_RENDERING_VER}-ogre2) + add_definitions(-DWITH_OGRE2) +endif() + +add_library(${PROJECT_NAME} + SHARED + MultibeamSonarSensor.cc +) + +target_include_directories(${PROJECT_NAME} + PUBLIC + ${gz-sensors${GZ_SENSORS_VER}_INCLUDE_DIRS} + ${gz-rendering${GZ_RENDERING_VER}_INCLUDE_DIRS} + ${gz-msgs${GZ_MSGS_VER}_INCLUDE_DIRS} + ${gz-transport${GZ_TRANSPORT_VER}_INCLUDE_DIRS} + ${gz-sim${GZ_SIM_VER}_INCLUDE_DIRS} +) +target_link_libraries(${PROJECT_NAME} ${PCL_LIBRARIES}) + +install(TARGETS ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +ament_target_dependencies(${PROJECT_NAME} + gz-sensors${GZ_SENSORS_VER} + ${GZ_RENDERING_TARGET} + gz-msgs${GZ_MSGS_VER} + gz-transport${GZ_TRANSPORT_VER} + gz-sim${GZ_SIM_VER} + rclcpp + sensor_msgs + rosidl_default_generators + PCL + pcl_conversions + OpenCV +) + + +# Environment hooks +ament_environment_hooks( + "${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in" +) + +ament_package() + + +# find_package(CUDAToolkit QUIET) +# if (CUDAToolkit_FOUND) +# enable_language(CUDA) +# message(STATUS "CUDA found, enabling CUDA support.") +# include_directories(${CUDA_INCLUDE_DIRS}) +# set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -arch=sm_60") + +# find_package(cv_bridge REQUIRED) +# find_package(OpenCV REQUIRED) +# find_package(rosidl_default_generators REQUIRED) +# find_package(PCL REQUIRED) +# find_package(pcl_ros REQUIRED) +# find_package(marine_acoustic_msgs REQUIRED) +# find_package(gz-sensors${GZ_SIM_VER} REQUIRED) +# set(GZ_SENSORS_VER ${gz-sensors8_VERSION_MAJOR}) + +# add_library(MultibeamSonarSystem SHARED +# src/MultibeamSonarSystem.cc +# ) + +# set_target_properties(MultibeamSonarSystem +# PROPERTIES CUDA_SEPARABLE_COMPILATION ON) + +# target_include_directories(MultibeamSonarSystem PRIVATE include) +# target_link_libraries(MultibeamSonarSystem +# gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER} +# gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER} +# gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER} +# ${CUDA_LIBRARIES} +# ${PCL_LIBRARIES} +# ${OpenCV_LIBRARIES} +# ) + +# ament_target_dependencies(MultibeamSonarSystem +# rclcpp +# std_msgs +# sensor_msgs +# geometry_msgs +# PCL +# OpenCV +# marine_acoustic_msgs +# ) +# install(TARGETS MultibeamSonarSystem +# DESTINATION lib/${PROJECT_NAME} +# ) +# else() +# message(STATUS "CUDA Toolkit not found: Skipping CUDA-specific targets") +# endif() \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/MultibeamSonarSensor.cc b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/MultibeamSonarSensor.cc new file mode 100644 index 00000000..666b67aa --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/MultibeamSonarSensor.cc @@ -0,0 +1,1100 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include +#include + +// TODO(hidmic): implement SVD in gazebo? +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include "MultibeamSonarSensor.hh" + +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace gz +{ +namespace sensors +{ +namespace +{ + +using RowMajorMatrix3d = Eigen::Matrix; + +/// \brief Axis-aligned patch on a plane, using image frame conventions. +template +class AxisAlignedPatch2 +{ +public: + AxisAlignedPatch2() = default; + +public: + AxisAlignedPatch2( + const gz::math::Vector2 & _topLeft, const gz::math::Vector2 & _bottomRight) + : topLeft(_topLeft), bottomRight(_bottomRight) + { + } + + /// \brief Scalar converting copy constructor +public: + template + // cppcheck-suppress noExplicitConstructor + AxisAlignedPatch2(const AxisAlignedPatch2 & _other) + { + this->topLeft.X(static_cast(_other.XMax())); + this->topLeft.Y(static_cast(_other.YMax())); + this->bottomRight.X(static_cast(_other.XMin())); + this->bottomRight.Y(static_cast(_other.YMin())); + } + +public: + T XMax() const { return this->topLeft.X(); } + +public: + T XMin() const { return this->bottomRight.X(); } + +public: + T XSize() const { return this->XMax() - this->XMin(); } + +public: + T YMax() const { return this->topLeft.Y(); } + +public: + T YMin() const { return this->bottomRight.Y(); } + +public: + T YSize() const { return this->YMax() - this->YMin(); } + + /// \brief Merge patch with `_other`. + /// \return a patch that includes both. +public: + AxisAlignedPatch2 & Merge(const AxisAlignedPatch2 & _other) + { + this->topLeft.Set( + std::max(this->topLeft.X(), _other.topLeft.X()), + std::max(this->topLeft.Y(), _other.topLeft.Y())); + this->bottomRight.Set( + std::min(this->bottomRight.X(), _other.bottomRight.X()), + std::min(this->bottomRight.Y(), _other.bottomRight.Y())); + return *this; + } + + /// \brief Flip patch, sending each corner to the opposite quadrant. +public: + AxisAlignedPatch2 Flip() const { return {-this->bottomRight, -this->topLeft}; } + + /// \brief Broadcast multiply corner coordinates by `_vector` + /// coordinates. + const AxisAlignedPatch2 operator*(gz::math::Vector2 _vector) const + { + return {this->topLeft * _vector, this->bottomRight * _vector}; + } + + /// \brief Broadcast divide corner coordinates by `_vector` + /// coordinates. + const AxisAlignedPatch2 operator/(gz::math::Vector2 _vector) const + { + return {this->topLeft / _vector, this->bottomRight / _vector}; + } + + /// \brief Broadcast sum corner coordinates with `_vector` coordinates. + const AxisAlignedPatch2 operator+(gz::math::Vector2 _vector) const + { + return {this->topLeft + _vector, this->bottomRight + _vector}; + } + + /// \brief Broadcast subtract corner coordinate with `_vector` + /// coordinates. + const AxisAlignedPatch2 operator-(gz::math::Vector2 _vector) const + { + return {this->topLeft - _vector, this->bottomRight - _vector}; + } + + /// \brief Upper-left corner i.e. (x, y) maxima +private: + gz::math::Vector2 topLeft; + + /// \brief Bottom-right corner i.e (x, y) minima +private: + gz::math::Vector2 bottomRight; +}; + +// Handy type definitions +using AxisAlignedPatch2d = AxisAlignedPatch2; +using AxisAlignedPatch2i = AxisAlignedPatch2; + +/// \brief Acoustic DVL beam, modelled as a circular cone with aperture +/// angle α and its apex at the origin. Its axis of symmetry is nominally +/// aligned with the x-axis of an x-forward, y-left, z-up frame +/// (following usual Gazebo frame conventions, typically facing +/// downwards). +/// +/// + The cone may be tilted w.r.t. the x-axis +/// /|\ and rotated about the same to accommodate +/// / | \ different beam arrangements, in that order. +/// / | \ That is, an extrinsic XY rotation applies. +/// / v \ / +/// x +/// |-------| +/// α +class AcousticBeam +{ + /// \brief Acoustic beam constructor. + /// \param[in] _id ID of the beam. Ought to be unique. + /// \param[in] _apertureAngle Aperture angle α of the beam. + /// \param[in] _rotationAngle Rotation angle ψ of the beam + /// i.e. a rotation about the x-axis of its frame. + /// \param[in] _tiltAngle Tilt angle φ of the + /// beam i.e. a rotation about the y-axis of its frame, + /// away from the x-axis. Must lie in the (-90, 90) degrees + /// interval. +public: + AcousticBeam( + const int _id, const gz::math::Angle _apertureAngle, const gz::math::Angle _rotationAngle, + const gz::math::Angle _tiltAngle) + : id(_id), + apertureAngle(_apertureAngle), + normalizedRadius(std::atan(_apertureAngle.Radian() / 2.)) + { + // Use extrinsic XY convention (as it is easier to reason about) + using Quaterniond = gz::math::Quaterniond; + this->transform.Rot() = Quaterniond::EulerToQuaternion(_rotationAngle.Radian(), 0., 0.) * + Quaterniond::EulerToQuaternion(0., _tiltAngle.Radian(), 0.); + this->axis = this->transform.Rot() * gz::math::Vector3d::UnitX; + const gz::math::Angle azimuthAngle = std::atan2(this->axis.Y(), this->axis.X()); + const gz::math::Angle inclinationAngle = std::atan2( + this->axis.Z(), std::sqrt(std::pow(this->axis.X(), 2.) + std::pow(this->axis.Y(), 2.))); + const gz::math::Vector2d topLeft{ + (azimuthAngle + _apertureAngle / 2.).Radian(), + (inclinationAngle + _apertureAngle / 2.).Radian()}; + const gz::math::Vector2d bottomRight{ + (azimuthAngle - _apertureAngle / 2.).Radian(), + (inclinationAngle - _apertureAngle / 2.).Radian()}; + this->sphericalFootprint = AxisAlignedPatch2d{topLeft, bottomRight}; + } + +public: + int Id() const { return this->id; } + +public: + const gz::math::Pose3d & Transform() const { return this->transform; } + +public: + const gz::math::Vector3d & Axis() const { return this->axis; } + +public: + double NormalizedRadius() const { return this->normalizedRadius; } + +public: + const gz::math::Angle & ApertureAngle() const { return this->apertureAngle; } + +public: + const AxisAlignedPatch2d & SphericalFootprint() const { return this->sphericalFootprint; } + +private: + int id; + +private: + gz::math::Angle apertureAngle; + +private: + double normalizedRadius; + +private: + gz::math::Pose3d transform; + +private: + gz::math::Vector3d axis; + +private: + AxisAlignedPatch2d sphericalFootprint; +}; + +/// \brief DVL acoustic beam reflecting target. +/// +/// Pose is defined w.r.t. to the beams frame. +struct ObjectTarget +{ + gz::math::Pose3d pose; + uint64_t entity; + std::string name; +}; + +/// \brief A time-varying vector field built on +/// per-axis time-varying volumetric data grids +/// +/// \see gz::math::InMemoryTimeVaryingVolumetricGrid +template +class InMemoryTimeVaryingVectorField +{ +public: + using SessionT = gz::math::InMemorySession; + +public: + using GridT = gz::math::InMemoryTimeVaryingVolumetricGrid; + + /// \brief Default constructor. +public: + InMemoryTimeVaryingVectorField() = default; + + /// \brief Constructor + /// \param[in] _xData X-axis volumetric data grid. + /// \param[in] _yData Y-axis volumetric data grid. + /// \param[in] _zData Z-axis volumetric data grid. +public: + explicit InMemoryTimeVaryingVectorField( + const GridT * _xData, const GridT * _yData, const GridT * _zData) + : xData(_xData), yData(_yData), zData(_zData) + { + if (this->xData) + { + this->xSession = this->xData->CreateSession(); + } + if (this->yData) + { + this->ySession = this->yData->CreateSession(); + } + if (this->zData) + { + this->zSession = this->zData->CreateSession(); + } + } + + /// \brief Advance vector field in time. + /// \param[in] _now Time to step data grids to. +public: + void StepTo(const std::chrono::steady_clock::duration & _now) + { + const T now = std::chrono::duration(_now).count(); + if (this->xData && this->xSession) + { + this->xSession = this->xData->StepTo(this->xSession.value(), now); + } + if (this->yData && this->ySession) + { + this->ySession = this->yData->StepTo(this->ySession.value(), now); + } + if (this->zData && this->zSession) + { + this->zSession = this->zData->StepTo(this->zSession.value(), now); + } + } + + /// \brief Look up vector field value, interpolating data grids. + /// \param[in] _pos Vector field argument. + /// \return vector field value at `_pos` +public: + gz::math::Vector3 LookUp(const gz::math::Vector3

& _pos) + { + auto outcome = gz::math::Vector3::Zero; + if (this->xData && this->xSession) + { + const auto interpolation = this->xData->LookUp(this->xSession.value(), _pos); + outcome.X(interpolation.value_or(0.)); + } + if (this->yData && this->ySession) + { + const auto interpolation = this->yData->LookUp(this->ySession.value(), _pos); + outcome.Y(interpolation.value_or(0.)); + } + if (this->zData && this->zSession) + { + const auto interpolation = this->zData->LookUp(this->ySession.value(), _pos); + outcome.Z(interpolation.value_or(0.)); + } + return outcome; + } + + /// \brief Session for x-axis volumetric data grid, if any. +private: + std::optional xSession{std::nullopt}; + + /// \brief Session for y-axis volumetric data grid, if any. +private: + std::optional ySession{std::nullopt}; + + /// \brief Session for z-axis volumetric data grid, if any. +private: + std::optional zSession{std::nullopt}; + + /// \brief X-axis volumetric data grid, if any. +private: + const GridT * xData{nullptr}; + + /// \brief Y-axis volumetric data grid, if any. +private: + const GridT * yData{nullptr}; + + /// \brief Z-axis volumetric data grid, if any. +private: + const GridT * zData{nullptr}; +}; + +} // namespace + +using namespace gz::msgs; + +/// \brief Implementation for MultibeamSonarSensor +class MultibeamSonarSensor::Implementation +{ + /// \brief SDF DOM object +public: + sdf::ElementPtr sensorSdf; + + /// \brief Sensor entity ID (for world state lookup) +public: + uint64_t entityId{0}; + + /// \brief true if Load() has been called and was successful +public: + bool initialized = false; + + /// \brief Initialize DVL sensor +public: + bool Initialize(MultibeamSonarSensor * _sensor); + + /// \brief Raw buffer of ray data. +public: + float * rayBuffer = nullptr; + + /// \brief Number of channels of the raw ray buffer +public: + const unsigned int kChannelCount = 3u; + + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + /// \brief Just a mutex for thread safety +public: + mutable std::mutex rayMutex; + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + + /// \brief Initialize beam arrangement for DVL sensor + /// + /// This primarily creates rendering sensors. +public: + bool InitializeBeamArrangement(MultibeamSonarSensor * _sensor); + + /// \brief Maximum range for beams. +public: + double maximumRange; + + /// \brief State of the world. +public: + const WorldState * worldState; + + /// \brief Depth sensor (i.e. a GPU raytracing sensor). +public: + gz::rendering::GpuRaysPtr depthSensor; + + /// \brief Image sensor (i.e. a camera sensor) to aid ray queries. +public: + gz::rendering::CameraPtr imageSensor; + + /// \brief Depth sensor intrinsic constants +public: + struct + { + gz::math::Vector2d offset; /// beams; + + /// \brief Rotation from sensor frame to reference frame. + /// + /// Useful to cope with different DVL frame conventions. +public: + gz::math::Quaterniond referenceFrameRotation; + + /// \brief Transform from sensor frame to acoustic beams' frame. + /// + /// I.e. x-forward, y-left, z-up (dvl sensor frame) rotates to + /// x-down, y-left, z-forward (acoustic beams' frame). +public: + const gz::math::Pose3d beamsFrameTransform{ + gz::math::Vector3d::Zero, gz::math::Quaterniond{0., GZ_PI / 2., 0.}}; + + /// \brief DVL acoustic beams' targets +public: + std::vector> beamTargets; + + /// \brief DVL acoustic beams' patches in depth scan frame. +public: + std::vector beamScanPatches; + + /// \brief The point cloud message. +public: + msgs::PointCloudPacked pointMsg; + + /// \brief Fill the point cloud packed message + /// \param[in] _rayBuffer Ray data buffer. +public: + void FillPointCloudMsg(const float * _rayBuffer); + + /// \brief Node to create a topic publisher with. +public: + gz::transport::Node node; + + /// \brief Publisher for messages. +public: + gz::transport::Node::Publisher pointPub; + + /// \brief Publisher for messages. +public: + gz::transport::Node::Publisher pointFloatPub; + + /// \brief Flag to indicate if sensor should be publishing estimates. +public: + bool publishingEstimates = false; +}; + +////////////////////////////////////////////////// +MultibeamSonarSensor::MultibeamSonarSensor() : dataPtr(new Implementation()) {} + +////////////////////////////////////////////////// +MultibeamSonarSensor::~MultibeamSonarSensor() +{ + this->dataPtr->depthConnection.reset(); + this->dataPtr->sceneChangeConnection.reset(); +} + +////////////////////////////////////////////////// +bool MultibeamSonarSensor::Load(const sdf::Sensor & _sdf) +{ + if (!gz::sensors::RenderingSensor::Load(_sdf)) + { + return false; + } + + // Check if this sensor is of the right type + if (_sdf.Type() != sdf::SensorType::CUSTOM) + { + gzerr << "Expected [" << this->Name() << "] sensor to be " + << "a Multibeam Sonar but found a " << _sdf.TypeStr() << "." << std::endl; + return false; + } + + sdf::ElementPtr elem = _sdf.Element(); + if (!elem->HasAttribute("gz:type")) + { + gzerr << "Missing 'gz:type' attribute " + << "for sensor [" << this->Name() << "]. " + << "Aborting load." << std::endl; + return false; + } + const auto type = elem->Get("gz:type"); + if (type != "multibeam_sonar") + { + gzerr << "Expected sensor [" << this->Name() << "] to be a " + << "DVL but it is of '" << type << "' type. Aborting load." << std::endl; + return false; + } + if (!elem->HasElement("gz:multibeam_sonar")) + { + gzerr << "Missing 'gz:multibeam_sonar' configuration for " + << "sensor [" << this->Name() << "]. " + << "Aborting load." << std::endl; + return false; + } + this->dataPtr->sensorSdf = elem->GetElement("gz:multibeam_sonar"); + + // Initialize the point message. + // \todo(anyone) The true value in the following function call forces + // the xyz and rgb fields to be aligned to memory boundaries. This is need + // by ROS1: https://github.com/ros/common_msgs/pull/77. Ideally, memory + // alignment should be configured. This same problem is in the + // RgbdCameraSensor. + msgs::InitPointCloudPacked( + this->dataPtr->pointMsg, this->FrameId(), true, + {{"xyz", msgs::PointCloudPacked::Field::FLOAT32}, + {"intensity", msgs::PointCloudPacked::Field::FLOAT32}, + {"ring", msgs::PointCloudPacked::Field::UINT16}}); + + // Instantiate interfaces + // Create the point cloud publisher + this->dataPtr->pointPub = + this->dataPtr->node.Advertise(this->Topic() + "/point_cloud"); + this->dataPtr->pointFloatPub = + this->dataPtr->node.Advertise(this->Topic() + "/point_cloud_float_vector"); + if (!this->dataPtr->pointPub) + { + gzerr << "Unable to create publisher on topic " + << "[" << this->Topic() << "] for sensor " + << "[" << this->Name() << "]" << std::endl; + return false; + } + + // Setup sensors + if (this->Scene()) + { + if (!this->dataPtr->Initialize(this)) + { + gzerr << "Failed to setup [" << this->Name() << "] sensor. " << std::endl; + return false; + } + } + + gzmsg << "Loaded [" << this->Name() << "] Multibeam Sonar sensor." << std::endl; + this->dataPtr->sceneChangeConnection = gz::sensors::RenderingEvents::ConnectSceneChangeCallback( + std::bind(&MultibeamSonarSensor::SetScene, this, std::placeholders::_1)); + + // ROS Initialization + + if (!rclcpp::ok()) + { + rclcpp::init(0, nullptr); + } + + this->ros_node_ = std::make_shared("multibeam_sonar_node"); + + this->pointCloudSub_ = this->ros_node_->create_subscription( + "/sensor/multibeam_sonar/point_cloud", 10, + std::bind(&MultibeamSonarSensor::pointCloudCallback, this, std::placeholders::_1)); + + return true; +} + +void MultibeamSonarSensor::pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) +{ + this->lock_.lock(); + + gzmsg << "Callback POINTCLOUD started" << std::endl; + + pcl::PointCloud::Ptr pcl_pointcloud(new pcl::PointCloud); + + gzmsg << "Converting ROS point cloud message to PCL format..." << std::endl; + + pcl::fromROSMsg(*msg, *pcl_pointcloud); + + gzmsg << "Point cloud converted. Number of points: " << pcl_pointcloud->size() << std::endl; + + if (this->dataPtr->pointMsg.width() == 0 || this->dataPtr->pointMsg.height() == 0) + { + gzmsg << "Error: PointCloud2 message dimensions are zero!" << std::endl; + } + else + { + unsigned int width = this->dataPtr->pointMsg.width(); + unsigned int height = this->dataPtr->pointMsg.height(); + + gzmsg << "Point cloud dimensions: width = " << width << ", height = " << height << std::endl; + + this->point_cloud_image_.create(height, width, CV_32FC1); + cv::MatIterator_ iter_image = this->point_cloud_image_.begin(); + + gzmsg << "Point cloud image matrix created" << std::endl; + } + + this->lock_.unlock(); + + gzmsg << "Callback POINTCLOUD finished" << std::endl; +} + +////////////////////////////////////////////////// +bool MultibeamSonarSensor::Load(sdf::ElementPtr _sdf) +{ + sdf::Sensor sdfSensor; + sdfSensor.Load(_sdf); + return this->Load(sdfSensor); +} + +////////////////////////////////////////////////// +bool MultibeamSonarSensor::Implementation::Initialize(MultibeamSonarSensor * _sensor) +{ + gzmsg << "Initializing [" << _sensor->Name() << "] sensor." << std::endl; + + if (!this->InitializeBeamArrangement(_sensor)) + { + gzerr << "Failed to initialize beam arrangement for " + << "[" << _sensor->Name() << "] sensor." << std::endl; + return false; + } + + gz::math::Pose3d referenceFrameTransform = + this->sensorSdf->Get("reference_frame", gz::math::Pose3d{}).first; + + this->referenceFrameRotation = referenceFrameTransform.Rot().Inverse(); + + gzmsg << "Initialized [" << _sensor->Name() << "] sensor." << std::endl; + this->initialized = true; + return true; +} + +////////////////////////////////////////////////// +bool MultibeamSonarSensor::Implementation::InitializeBeamArrangement(MultibeamSonarSensor * _sensor) +{ + this->beams.clear(); + this->beamTargets.clear(); + + this->depthSensor = _sensor->Scene()->CreateGpuRays(_sensor->Name() + "_depth_sensor"); + if (!this->depthSensor) + { + gzerr << "Failed to create Depth (GPU Ray) sensor for " + << "for [" << _sensor->Name() << "] sensor." << std::endl; + return false; + } + + // Read ray definition from SDF + sdf::ElementPtr rayElement = this->sensorSdf->GetElement("ray"); + if (!rayElement) + { + gzerr << "No beam properties(format of GPU Ray) specified for " + << "[" << _sensor->Name() << "] sensor" << std::endl; + return false; + } + const bool useDegrees = rayElement->Get("degrees", false).first; + const gz::math::Angle angleUnit = useDegrees ? GZ_DTOR(1.) : 1.; + + // -------- Assign depth sensor properties + sdf::ElementPtr rangeElement = rayElement->GetElement("range"); + const double minimumRange = rangeElement->Get("min", 0.1).first; + gzmsg << "Setting minimum range to " << minimumRange << " m for [" << _sensor->Name() + << "] sensor." << std::endl; + this->depthSensor->SetNearClipPlane(minimumRange); + this->maximumRange = rangeElement->Get("max", 5.).first; + gzmsg << "Setting maximum range to " << this->maximumRange << " m for [" << _sensor->Name() + << "] sensor." << std::endl; + this->depthSensor->SetFarClipPlane(this->maximumRange); + + // Mask ranges outside of min/max to +/- inf, as per REP 117 + this->depthSensor->SetClamp(false); + + sdf::ElementPtr horizontalElement = rayElement->GetElement("scan")->GetElement("horizontal"); + const double horizAngleMin = horizontalElement->Get("min_angle", -M_PI / 4.0).first; + const double horizAngleMax = horizontalElement->Get("max_angle", M_PI / 4.0).first; + + sdf::ElementPtr verticalElement = rayElement->GetElement("scan")->GetElement("vertical"); + const double verticalAngleMin = verticalElement->Get("min_angle", -M_PI / 8.0).first; + const double verticalAngleMax = verticalElement->Get("max_angle", M_PI / 8.0).first; + + const int beamCount = horizontalElement->Get("beams", 256).first; + const int rayCount = verticalElement->Get("rays", 3).first; + + // ---- Construct AcousticBeam + // Initialize beamId + int beamId = 0; + + // Iterate through the rays + for (int v = 0; v < rayCount; ++v) + { + for (int h = 0; h < beamCount; ++h) + { + // Calculate beam angles + gz::math::Angle beamApertureAngle = + gz::math::Angle(verticalAngleMax - verticalAngleMin) * angleUnit; + gz::math::Angle beamRotationAngle = + gz::math::Angle(horizAngleMin + (h * (horizAngleMax - horizAngleMin) / beamCount)) * + angleUnit; + gz::math::Angle beamTiltAngle = + gz::math::Angle(verticalAngleMin + (v * (verticalAngleMax - verticalAngleMin) / rayCount)) * + angleUnit; + + // Normalize angles + beamApertureAngle = beamApertureAngle.Normalized(); + beamRotationAngle = beamRotationAngle.Normalized(); + beamTiltAngle = beamTiltAngle.Normalized(); + + // Build acoustic beam + this->beams.push_back( + AcousticBeam{beamId, beamApertureAngle, beamRotationAngle, beamTiltAngle}); + + // Increment beamId + ++beamId; + } + } + + // Add as many (still null) targets as beams + this->beamTargets.resize(this->beams.size()); + + // Aggregate all beams' footprint in spherical coordinates into one + AxisAlignedPatch2d beamsSphericalFootprint; + for (const auto & beam : this->beams) + { + beamsSphericalFootprint.Merge(beam.SphericalFootprint()); + } + // Rendering sensors' FOV must be symmetric about its main axis + beamsSphericalFootprint.Merge(beamsSphericalFootprint.Flip()); + + this->depthSensor->SetAngleMin(beamsSphericalFootprint.XMin()); + this->depthSensor->SetAngleMax(beamsSphericalFootprint.XMax()); + auto horizontalRayCount = beamCount; + if (horizontalRayCount % 2 == 0) + { + ++horizontalRayCount; // ensure odd + } + this->depthSensor->SetRayCount(horizontalRayCount); + + this->depthSensor->SetVerticalAngleMin(beamsSphericalFootprint.YMin()); + this->depthSensor->SetVerticalAngleMax(beamsSphericalFootprint.YMax()); + auto verticalRayCount = rayCount; + if (verticalRayCount % 2 == 0) + { + ++verticalRayCount; // ensure odd + } + + this->depthSensor->SetVerticalRayCount(verticalRayCount); + + auto & intrinsics = this->depthSensorIntrinsics; + intrinsics.offset.X(beamsSphericalFootprint.XMin()); + intrinsics.offset.Y(beamsSphericalFootprint.YMin()); + intrinsics.step.X(beamsSphericalFootprint.XSize() / (horizontalRayCount - 1)); + intrinsics.step.Y(beamsSphericalFootprint.YSize() / (verticalRayCount - 1)); + + // Pre-compute scan indices covered by beam spherical + // footprints for speed during scan iteration + this->beamScanPatches.clear(); + for (const auto & beam : this->beams) + { + this->beamScanPatches.push_back( + AxisAlignedPatch2i{(beam.SphericalFootprint() - intrinsics.offset) / intrinsics.step}); + } + + // _sensor->Scene()->RootVisual()->AddChild(this->depthSensor); + + this->depthSensor->SetVisibilityMask(GZ_VISIBILITY_ALL); + + _sensor->AddSensor(this->depthSensor); + + // Set the values on the point message. + this->pointMsg.set_width(this->depthSensor->RangeCount()); + this->pointMsg.set_height(this->depthSensor->VerticalRangeCount()); + this->pointMsg.set_row_step(this->pointMsg.point_step() * this->pointMsg.width()); + + this->imageSensor = _sensor->Scene()->CreateCamera(_sensor->Name() + "_image_sensor"); + if (!this->imageSensor) + { + gzerr << "Failed to create image sensor for " + << "for [" << _sensor->Name() << "] sensor." << std::endl; + return false; + } + + this->imageSensor->SetImageWidth(horizontalRayCount); + this->imageSensor->SetImageHeight(verticalRayCount); + + this->imageSensor->SetNearClipPlane(minimumRange); + this->imageSensor->SetFarClipPlane(this->maximumRange); + this->imageSensor->SetAntiAliasing(2); + + this->imageSensor->SetAspectRatio( + beamsSphericalFootprint.XSize() / beamsSphericalFootprint.YSize()); + this->imageSensor->SetHFOV(beamsSphericalFootprint.XSize()); + this->imageSensor->SetVisibilityMask(~GZ_VISIBILITY_GUI); + + _sensor->AddSensor(this->imageSensor); + + this->depthConnection = this->depthSensor->ConnectNewGpuRaysFrame(std::bind( + &MultibeamSonarSensor::Implementation::OnNewFrame, this, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5)); + + return true; +} + +////////////////////////////////////////////////// +std::vector MultibeamSonarSensor::RenderingSensors() const +{ + return {this->dataPtr->depthSensor, this->dataPtr->imageSensor}; +} + +// Simplified function to only process point cloud +void MultibeamSonarSensor::Implementation::OnNewFrame( + const float * _scan, unsigned int _width, unsigned int _height, unsigned int _channels, + const std::string & /*_format*/) +{ + // Lock the ray buffer for thread safety + std::lock_guard lock(this->rayMutex); + + // Total number of points in the scan + unsigned int samples = _width * _height * _channels; + unsigned int rayBufferSize = samples * sizeof(float); + + // Allocate memory for the ray buffer if not already allocated + if (!this->rayBuffer) + { + this->rayBuffer = new float[samples]; + } + + // Copy the incoming scan data into the ray buffer + memcpy(this->rayBuffer, _scan, rayBufferSize); + + // Further processing of the point cloud can go here, if needed +} + +///////////////////////////////////////////////// +void MultibeamSonarSensor::SetScene(gz::rendering::ScenePtr _scene) +{ + // APIs make it possible for the scene pointer to change + if (this->Scene() != _scene) + { + // TODO(anyone) Remove camera from scene + this->dataPtr->depthSensor = nullptr; + this->dataPtr->imageSensor = nullptr; + if (this->dataPtr->rayBuffer) + { + delete[] this->dataPtr->rayBuffer; + this->dataPtr->rayBuffer = nullptr; + } + RenderingSensor::SetScene(_scene); + if (!this->dataPtr->initialized) + { + if (!this->dataPtr->Initialize(this)) + { + gzerr << "Failed to initialize " + << "[" << this->Name() << "]" + << " sensor." << std::endl; + } + } + } +} + +////////////////////////////////////////////////// +void MultibeamSonarSensor::SetWorldState(const WorldState & _state) +{ + this->dataPtr->worldState = &_state; +} +////////////////////////////////////////////////// +void MultibeamSonarSensor::SetEnvironmentalData(const EnvironmentalData & _data) {} + +////////////////////////////////////////////////// +void MultibeamSonarSensor::SetEntity(uint64_t _entityId) { this->dataPtr->entityId = _entityId; } + +////////////////////////////////////////////////// +bool MultibeamSonarSensor::Update(const std::chrono::steady_clock::duration & _now) +{ + GZ_PROFILE("MultibeamSonarSensor::Update"); + if (!this->dataPtr->initialized || this->dataPtr->entityId == 0) + { + gzerr << "Not initialized, update ignored." << std::endl; + return false; + } + + if (!this->dataPtr->depthSensor) + { + gzerr << "Depth (GpuRays) Sensor for Multibeam Sonar doesn't exist.\n"; + return false; + } + + // const gz::math::Pose3d beamsFramePose = this->Pose() * this->dataPtr->beamsFrameTransform; + // this->dataPtr->depthSensor->SetLocalPose(beamsFramePose); + // this->dataPtr->imageSensor->SetLocalPose(beamsFramePose); + + // Generate sensor data + this->Render(); + + if (this->dataPtr->pointPub.HasConnections()) + { + // Set the time stamp + *this->dataPtr->pointMsg.mutable_header()->mutable_stamp() = msgs::Convert(_now); + // Set frame_id + for (auto i = 0; i < this->dataPtr->pointMsg.mutable_header()->data_size(); ++i) + { + if ( + this->dataPtr->pointMsg.mutable_header()->data(i).key() == "frame_id" && + this->dataPtr->pointMsg.mutable_header()->data(i).value_size() > 0) + { + this->dataPtr->pointMsg.mutable_header()->mutable_data(i)->set_value(0, this->FrameId()); + } + } + + this->dataPtr->FillPointCloudMsg(this->dataPtr->rayBuffer); + + // For the point cloud visualization in gazebo + // https://github.com/gazebosim/gz-gui/pull/346 + { + this->AddSequence(this->dataPtr->pointMsg.mutable_header()); + GZ_PROFILE("MultibeamSonarSensor::Update Publish point cloud"); + this->dataPtr->pointPub.Publish(this->dataPtr->pointMsg); + } + } + + return true; +} + +////////////////////////////////////////////////// +void MultibeamSonarSensor::PostUpdate(const std::chrono::steady_clock::duration & _now) +{ + GZ_PROFILE("MultibeamSonarSensor::PostUpdate"); + + if (!this->dataPtr->worldState) + { + gzwarn << "No world state available, " + << "cannot estimate velocities." << std::endl; + return; + } + rclcpp::spin_some(this->ros_node_); + + for (size_t i = 0; i < this->dataPtr->beams.size(); ++i) + { + auto & beamTarget = this->dataPtr->beamTargets[i]; + if (beamTarget) + { + // TODO(hidmic): use shader to fetch target entity id + const gz::math::Vector2i pixel = this->dataPtr->imageSensor->Project(beamTarget->pose.Pos()); + auto visual = this->dataPtr->imageSensor->VisualAt(pixel); + if (visual) + { + if (visual->HasUserData("gazebo-entity")) + { + auto user_data = visual->UserData("gazebo-entity"); + beamTarget->entity = std::get(user_data); + } + else + { + gzdbg << "No entity associated to [" << visual->Name() << "]" + << " visual. Assuming it is static w.r.t. the world." << std::endl; + } + } + } + } + + // auto * headerMessage = waterMassModeMessage.mutable_header(); + // auto frame = headerMessage->add_data(); + // frame->set_key("frame_id"); + // frame->add_value(this->FrameId()); + // this->AddSequence(headerMessage, "doppler_velocity_log"); + // this->dataPtr->pointPub.Publish(waterMassModeMessage); +} + +////////////////////////////////////////////////// +bool MultibeamSonarSensor::HasConnections() const +{ + return this->dataPtr->pointPub && this->dataPtr->pointPub.HasConnections(); +} + +////////////////////////////////////////////////// +void MultibeamSonarSensor::Implementation::FillPointCloudMsg(const float * _rayBuffer) +{ + uint32_t width = this->pointMsg.width(); + uint32_t height = this->pointMsg.height(); + unsigned int channels = 3; + + float angleStep = (this->depthSensor->AngleMax() - this->depthSensor->AngleMin()).Radian() / + (this->depthSensor->RangeCount() - 1); + + float verticleAngleStep = + (this->depthSensor->VerticalAngleMax() - this->depthSensor->VerticalAngleMin()).Radian() / + (this->depthSensor->VerticalRangeCount() - 1); + + // Angles of ray currently processing, azimuth is horizontal, inclination + // is vertical + float inclination = this->depthSensor->VerticalAngleMin().Radian(); + + std::string * msgBuffer = this->pointMsg.mutable_data(); + msgBuffer->resize(this->pointMsg.row_step() * this->pointMsg.height()); + char * msgBufferIndex = msgBuffer->data(); + // Set Pointcloud as dense. Change if invalid points are found. + bool isDense{true}; + // Iterate over scan and populate point cloud + for (uint32_t j = 0; j < height; ++j) + { + float azimuth = this->depthSensor->AngleMin().Radian(); + + for (uint32_t i = 0; i < width; ++i) + { + // Index of current point, and the depth value at that point + auto index = j * width * channels + i * channels; + float depth = _rayBuffer[index]; + // Validate Depth/Radius and update pointcloud density flag + if (isDense) + { + isDense = !(gz::math::isnan(depth) || std::isinf(depth)); + } + + float intensity = _rayBuffer[index + 1]; + uint16_t ring = j; + + int fieldIndex = 0; + + // Convert spherical coordinates to Cartesian for pointcloud + // See https://en.wikipedia.org/wiki/Spherical_coordinate_system + *reinterpret_cast(msgBufferIndex + this->pointMsg.field(fieldIndex++).offset()) = + depth * std::cos(inclination) * std::cos(azimuth); + + *reinterpret_cast(msgBufferIndex + this->pointMsg.field(fieldIndex++).offset()) = + depth * std::cos(inclination) * std::sin(azimuth); + + *reinterpret_cast(msgBufferIndex + this->pointMsg.field(fieldIndex++).offset()) = + depth * std::sin(inclination); + + // Intensity + *reinterpret_cast(msgBufferIndex + this->pointMsg.field(fieldIndex++).offset()) = + intensity; + + // Ring + *reinterpret_cast(msgBufferIndex + this->pointMsg.field(fieldIndex++).offset()) = + ring; + + // Move the index to the next point. + msgBufferIndex += this->pointMsg.point_step(); + + azimuth += angleStep; + } + inclination += verticleAngleStep; + } + this->pointMsg.set_is_dense(isDense); +} + +} // namespace sensors +} // namespace gz \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/MultibeamSonarSensor.hh b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/MultibeamSonarSensor.hh new file mode 100644 index 00000000..4c94cf7d --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/MultibeamSonarSensor.hh @@ -0,0 +1,116 @@ +#ifndef GZ_SENSORS_MULTIBEAMSONAR_HH_ +#define GZ_SENSORS_MULTIBEAMSONAR_HH_ + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include // For OpenCV Mat +#include +#include + +namespace gz +{ +namespace sensors +{ +/// \brief Kinematic state for an entity in the world. +/// +/// All quantities are defined w.r.t. the world frame. +struct EntityKinematicState +{ + gz::math::Pose3d pose; + gz::math::Vector3d linearVelocity; + gz::math::Vector3d angularVelocity; +}; + +/// \brief Kinematic state for all entities in the world. +using WorldKinematicState = std::unordered_map; + +/// \brief Kinematic state for all entities in the world. +struct WorldState +{ + WorldKinematicState kinematics; + gz::math::SphericalCoordinates origin; +}; + +class MultibeamSonarSensor : public gz::sensors::RenderingSensor +{ +public: + MultibeamSonarSensor(); + +public: + ~MultibeamSonarSensor(); + + /// Inherits documentation from parent class +public: + virtual bool Load(const sdf::Sensor & _sdf) override; + + /// Inherits documentation from parent class +public: + virtual bool Load(sdf::ElementPtr _sdf) override; + + /// Inherits documentation from parent class +public: + virtual bool Update(const std::chrono::steady_clock::duration & _now) override; + + /// Perform any sensor updates after the rendering pass +public: + virtual void PostUpdate(const std::chrono::steady_clock::duration & _now); + + /// Inherits documentation from parent class +public: + void SetScene(gz::rendering::ScenePtr _scene) override; + + /// \brief Set this sensor's entity ID (for world state lookup). +public: + void SetEntity(uint64_t entity); + + /// \brief Set world `_state` to support DVL water and bottom-tracking. +public: + void SetWorldState(const WorldState & _state); + + /// \brief Set environmental `_data` to support DVL water-tracking. +public: + void SetEnvironmentalData(const EnvironmentalData & _data); + + /// \brief Inherits documentation from parent class +public: + virtual bool HasConnections() const override; + + /// \brief Yield rendering sensors that underpin the implementation. + /// + /// \internal +public: + std::vector RenderingSensors() const; + +private: + class Implementation; + +private: + std::mutex lock_; + +private: + std::unique_ptr dataPtr; + + // ROS node handle member + std::shared_ptr ros_node_; + // Subscription for PointCloud2 messages + rclcpp::Subscription::SharedPtr pointCloudSub_; + + void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg); + +private: + cv::Mat point_cloud_image_; // Point cloud image + cv::Mat point_cloud_normal_image_; // Point cloud normal image +}; + +} // namespace sensors +} // namespace gz + +#endif // GZ_SENSORS_MULTIBEAMSONAR_HH_ diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/hooks/multibeam_sonar.dsv.in b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/hooks/multibeam_sonar.dsv.in new file mode 100644 index 00000000..07f53dcf --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/hooks/multibeam_sonar.dsv.in @@ -0,0 +1,2 @@ +prepend-non-duplicate;GZ_SIM_SYSTEM_PLUGIN_PATH;lib/@PROJECT_NAME@/ +prepend-non-duplicate;LD_LIBRARY_PATH;lib/@PROJECT_NAME@/ diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/package.xml b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/package.xml new file mode 100644 index 00000000..431054ba --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar/package.xml @@ -0,0 +1,25 @@ + + + multibeam_sonar + 0.0.1 + DAVE multibeam sonar sensor + Woen-Sug Choi + Helena Moyen + Gaurav kumar + Apache 2.0 + geometry_msgs + pcl_conversions + libpcl-all-dev + libpcl-all + ament_cmake + ament_lint_auto + dave_interfaces + protobuf + marine_acoustic_msgs + + dave_interfaces + + + ament_cmake + + \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/CMakeLists.txt b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/CMakeLists.txt new file mode 100644 index 00000000..7f57f3de --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/CMakeLists.txt @@ -0,0 +1,18 @@ +cmake_minimum_required(VERSION 3.8) +project(dave_multibeam_sonar_demo) + +find_package(ament_cmake REQUIRED) + +install( + DIRECTORY launch + DESTINATION share/${PROJECT_NAME} +) + +install( + DIRECTORY rviz + DESTINATION share/${PROJECT_NAME} +) + +ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in") + +ament_package() diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/hooks/dave_multibeam_sonar_demo.dsv.in b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/hooks/dave_multibeam_sonar_demo.dsv.in new file mode 100644 index 00000000..000c1b2d --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/hooks/dave_multibeam_sonar_demo.dsv.in @@ -0,0 +1 @@ +prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;@CMAKE_INSTALL_PREFIX@/share/@PROJECT_NAME@ \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/launch/multibeam_sonar_demo.launch.py b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/launch/multibeam_sonar_demo.launch.py new file mode 100644 index 00000000..73ca2e94 --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/launch/multibeam_sonar_demo.launch.py @@ -0,0 +1,91 @@ +# Copyright 2019 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import IncludeLaunchDescription +from launch.conditions import IfCondition +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from launch_ros.actions import Node + + +def generate_launch_description(): + pkg_dave_demos = get_package_share_directory("dave_demos") + multibeam_sonar_sim = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(pkg_dave_demos, "launch", "dave_sensor.launch.py") + ), + launch_arguments={ + "namespace": "blueview_p900", + "world_name": "dave_multibeam_sonar", + "paused": "false", + "x": "4", + "z": "0.5", + "yaw": "3.14", + }.items(), + ) + + # RViz + pkg_dave_multibeam_sonar_demo = get_package_share_directory("dave_multibeam_sonar_demo") + rviz = Node( + package="rviz2", + executable="rviz2", + arguments=[ + "-d", + os.path.join(pkg_dave_multibeam_sonar_demo, "rviz", "multibeam_sonar.rviz"), + ], + condition=IfCondition(LaunchConfiguration("rviz")), + ) + + # Bridge + bridge = Node( + package="ros_gz_bridge", + executable="parameter_bridge", + arguments=[ + "/sensor/camera@sensor_msgs/msg/Image@gz.msgs.Image", + "/sensor/camera_info@sensor_msgs/msg/CameraInfo@gz.msgs.CameraInfo", + "/sensor/depth_camera@sensor_msgs/msg/Image@gz.msgs.Image", + "/sensor/multibeam_sonar/point_cloud@sensor_msgs/msg/PointCloud2@gz.msgs.PointCloudPacked", + ], + output="screen", + ) + + # ! TODO: Add a static transform publisher for the multibeam sonar + # TF (Not sure about this....) + tf_node = Node( + package="tf2_ros", + executable="static_transform_publisher", + arguments=[ + "--frame-id", + "world", + "--child-frame-id", + "blueview_p900/blueview_p900_base_link/multibeam_sonar", + ], + ) + + return LaunchDescription( + [ + multibeam_sonar_sim, + DeclareLaunchArgument("rviz", default_value="true", description="Open RViz."), + bridge, + rviz, + tf_node, + ] + ) diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/package.xml b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/package.xml new file mode 100644 index 00000000..bd5aa9dd --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/package.xml @@ -0,0 +1,12 @@ + + + dave_multibeam_sonar_demo + 0.1.0 + A package for multibeam sonar demo files. + Woen-Sug Choi + MIT + ament_cmake + + ament_cmake + + \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/rviz/multibeam_sonar.rviz b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/rviz/multibeam_sonar.rviz new file mode 100644 index 00000000..610fb45c --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_demo/rviz/multibeam_sonar.rviz @@ -0,0 +1,205 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 138 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Camera1 + - /Camera1/Status1 + - /Camera1/Topic1 + - /Depth Camera1 + - /Depth Camera1/Topic1 + - /PointCloud21 + - /PointCloud21/Status1 + Splitter Ratio: 0.5 + Tree Height: 785 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + 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 + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensor/camera + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Depth Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: System Default + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensor/depth_camera + 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_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + 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: PointCloud2 + Position Transformer: "" + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /sensor/multibeam_sonar/point_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 17.623416900634766 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.7903980016708374 + Target Frame: + Value: Orbit (rviz_default_plugins) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + Depth Camera: + collapsed: false + Displays: + collapsed: false + Height: 1773 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000003c7000005e3fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b200fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000700000040d0000018600fffffffb0000000a005600690065007700730100000489000001ca0000013800fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000002ec000005e3fc0200000004fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000c00430061006d0065007200610100000070000002fe0000004c00fffffffb0000001800440065007000740068002000430061006d006500720061010000037a000002d90000004c00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e1000001970000000300000bcf0000005efc0100000002fb0000000800540069006d0065010000000000000bcf0000047a00fffffffb0000000800540069006d0065010000000000000450000000000000000000000504000005e300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 3023 + X: 401 + Y: 368 diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/CMakeLists.txt b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/CMakeLists.txt new file mode 100644 index 00000000..22f5860f --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/CMakeLists.txt @@ -0,0 +1,114 @@ +cmake_minimum_required(VERSION 3.11.0 FATAL_ERROR) +project(multibeam_sonar_system) + +find_package(ament_cmake REQUIRED) +find_package(gz-cmake3 REQUIRED) +find_package(gz-common5 REQUIRED COMPONENTS profiler) +find_package(gz-plugin2 REQUIRED COMPONENTS register) +find_package(gz-rendering8 REQUIRED OPTIONAL_COMPONENTS ogre ogre2) +find_package(gz-sim8 REQUIRED) +find_package(gz-sensors8 REQUIRED) + +set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR}) +set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR}) +set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR}) +set(GZ_RENDERING_VER ${gz-rendering8_VERSION_MAJOR}) +set(GZ_SENSORS_VER ${gz-sensors8_VERSION_MAJOR}) + +if(TARGET gz-rendering${GZ_RENDERING_VER}::ogre) + set(HAVE_OGRE TRUE) + set(GZ_RENDERING_TARGET gz-rendering${GZ_RENDERING_VER}-ogre) + add_definitions(-DWITH_OGRE) +endif() + +if(TARGET gz-rendering${GZ_RENDERING_VER}::ogre2) + set(HAVE_OGRE2 TRUE) + set(GZ_RENDERING_TARGET gz-rendering${GZ_RENDERING_VER}-ogre2) + add_definitions(-DWITH_OGRE2) +endif() + + +add_subdirectory(../multibeam_sonar ${CMAKE_BINARY_DIR}/multibeam_sonar) + +add_library(${PROJECT_NAME} SHARED MultibeamSonarSystem.cc) +target_link_libraries(${PROJECT_NAME} + gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} + gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER} + gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER} + gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER} + multibeam_sonar +) +target_include_directories(${PROJECT_NAME} + PUBLIC + ../multibeam_sonar +) + +ament_target_dependencies(${PROJECT_NAME} + gz-common${GZ_COMMON_VER} + ${GZ_RENDERING_TARGET} + gz-plugin${GZ_PLUGIN_VER} + gz-sim${GZ_SIM_VER} + gz-sensors${GZ_SENSORS_VER} +) + +# Install targets +install(TARGETS ${PROJECT_NAME} + DESTINATION lib/${PROJECT_NAME} +) + +# Environment hooks +ament_environment_hooks( + "${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in" +) + +ament_package() + + +# find_package(CUDAToolkit QUIET) +# if(CUDAToolkit_FOUND) +# enable_language(CUDA) +# message(STATUS "CUDA found, enabling CUDA support.") +# include_directories(${CUDA_INCLUDE_DIRS}) +# set(CUDA_NVCC_FLAGS "${CUDA_NVCC_FLAGS} -arch=sm_60") + +# find_package(cv_bridge REQUIRED) +# find_package(OpenCV REQUIRED) +# find_package(rosidl_default_generators REQUIRED) +# find_package(PCL REQUIRED) +# find_package(pcl_ros REQUIRED) +# find_package(marine_acoustic_msgs REQUIRED) +# find_package(gz-sensors${GZ_SIM_VER} REQUIRED) +# set(GZ_SENSORS_VER ${gz-sensors8_VERSION_MAJOR}) + +# add_library(MultibeamSonarSystem SHARED +# src/MultibeamSonarSystem.cc +# ) + +# set_target_properties(MultibeamSonarSystem +# PROPERTIES CUDA_SEPARABLE_COMPILATION ON) + +# target_include_directories(MultibeamSonarSystem PRIVATE include) +# target_link_libraries(MultibeamSonarSystem +# gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER} +# gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER} +# gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER} +# ${CUDA_LIBRARIES} +# ${PCL_LIBRARIES} +# ${OpenCV_LIBRARIES} +# ) + +# ament_target_dependencies(MultibeamSonarSystem +# rclcpp +# std_msgs +# sensor_msgs +# geometry_msgs +# PCL +# OpenCV +# marine_acoustic_msgs +# ) +# install(TARGETS MultibeamSonarSystem +# DESTINATION lib/${PROJECT_NAME} +# ) +# else() +# message(STATUS "CUDA Toolkit not found: Skipping CUDA-specific targets") +# endif() \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/MultibeamSonarSystem.cc b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/MultibeamSonarSystem.cc new file mode 100644 index 00000000..2f28c240 --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/MultibeamSonarSystem.cc @@ -0,0 +1,706 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +#include +#include +#include +#include + +#include + +#include "./../multibeam_sonar/MultibeamSonarSensor.hh" +#include "MultibeamSonarSystem.hh" + +namespace gz +{ +namespace sim +{ +namespace requests +{ +/// \brief A request for sensor creation. +struct CreateSensor +{ + sdf::Sensor sdf; + gz::sim::Entity entity; + gz::sim::Entity parent; + std::string parentName; +}; + +/// \brief A request for sensor destruction. +struct DestroySensor +{ + /// \brief Entity to destroy + gz::sim::Entity entity; +}; + +/// \brief A request for a world state update for sensors. +struct SetWorldState +{ + /// \brief World state + gz::sensors::WorldState worldState; +}; + +/// \brief A request for an environmental data update for sensors. +struct SetEnvironmentalData +{ + /// \brief Environment data + std::shared_ptr environmentalData; +}; + +/// \brief Union request type. +using SomeRequest = std::variant; + +} // namespace requests +} // namespace sim +} // namespace gz + +/// \brief Private data class. +class gz::sim::systems::MultibeamSonarSystem::Implementation +{ + /// \brief Callback invoked in the rendering thread before a rendering update +public: + void OnPreRender(); + + /// \brief Callback invoked in the rendering thread during a rendering update +public: + void OnRender(); + + /// \brief Callback invoked in the rendering thread after a rendering update +public: + void OnPostRender(); + + /// \brief Callback invoked in the rendering thread before stopping +public: + void OnRenderTeardown(); + + /// \brief Find visual with given entity id + /// \param[in] _scene Pointer to Scene + /// \param[in] _entity Entity ID +public: + gz::rendering::VisualPtr FindEntityVisual( + gz::rendering::ScenePtr _scene, gz::sim::Entity _entity); + + /// \brief Overload to handle sensor creation requests. +public: + void Handle(requests::CreateSensor _request); + + /// \brief Overload to handle sensor destruction requests. +public: + void Handle(requests::DestroySensor _request); + + /// \brief Overload to handle world state update requests. +public: + void Handle(requests::SetWorldState _request); + + /// \brief Overload to handle environment data update requests. +public: + void Handle(requests::SetEnvironmentalData _request); + + /// \brief Implementation for Configure() hook. +public: + void DoConfigure( + const gz::sim::Entity & _entity, const std::shared_ptr & _sdf, + gz::sim::EntityComponentManager & _ecm, gz::sim::EventManager & _eventMgr); + + /// \brief Implementation for PreUpdate() hook. +public: + void DoPreUpdate(const gz::sim::UpdateInfo & _info, gz::sim::EntityComponentManager & _ecm); + + /// \brief Implementation for Update() hook. +public: + void DoUpdate(const gz::sim::UpdateInfo & _info, gz::sim::EntityComponentManager & _ecm); + + /// \brief Implementation for PostUpdate() hook. +public: + void DoPostUpdate( + const gz::sim::UpdateInfo & _info, const gz::sim::EntityComponentManager & _ecm); + + /// \brief State of all entities in the world in simulation thread +public: + std::optional latestWorldState; + + /// \brief State of all entities in the world in simulation thread +public: + std::shared_ptr latestEnvironmentalData; + + /// \brief Connection to the pre-render event. +public: + gz::common::ConnectionPtr preRenderConn; + + /// \brief Connection to the render event. +public: + gz::common::ConnectionPtr renderConn; + + /// \brief Connection to the post-render event. +public: + gz::common::ConnectionPtr postRenderConn; + + /// \brief Connection to the render teardown event. +public: + gz::common::ConnectionPtr renderTeardownConn; + + /// \brief Pointer to the event manager +public: + gz::sim::EventManager * eventMgr = nullptr; + + //// \brief Pointer to the rendering scene +public: + gz::rendering::ScenePtr scene; + + /// \brief Sensor managers +public: + gz::sensors::Manager sensorManager; + + /// \brief Entities of known sensors (in simulation thread) +public: + std::unordered_set knownSensorEntities; + + /// \brief Sensor ID per sensor entity mapping in rendering thread +public: + std::unordered_map sensorIdPerEntity; + + /// \brief IDs of sensors updated in the last rendering pass +public: + std::vector updatedSensorIds; + + /// \brief Queue of requests from simulation thread to rendering thread +public: + std::vector perStepRequests; + + /// \brief Mutex to synchronize access to queued requests +public: + std::mutex requestsMutex; + + /// \brief Create/Destroy sensor requests queue, popped by the rendering + /// thread. +public: + std::vector queuedRequests; + + /// \brief SetWorldState requests queue, popped by the rendering thread. +public: + std::vector queuedSetWorldRequests; + + /// \brief Flag for pending (ie. queued) requests. +public: + std::atomic pendingRequests{false}; + + /// \brief Flag for pending (ie. queued) set world state requests. +public: + std::atomic pendingSetWorldRequests{false}; + + /// \brief Flag for +public: + bool needsUpdate{false}; + + /// \brief Current simulation time. +public: + std::chrono::steady_clock::duration simTime{0}; + + /// \brief Current simulation time. +public: + std::chrono::steady_clock::duration nextUpdateTime{std::chrono::steady_clock::duration::max()}; + + /// \brief Mutex to protect current simulation times +public: + std::mutex timeMutex; +}; + +using namespace gz; +using namespace sim; +using namespace systems; + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::DoConfigure( + const gz::sim::Entity &, const std::shared_ptr &, + gz::sim::EntityComponentManager &, gz::sim::EventManager & _eventMgr) +{ + this->preRenderConn = + _eventMgr.Connect(std::bind(&Implementation::OnPreRender, this)); + + this->renderConn = + _eventMgr.Connect(std::bind(&Implementation::OnRender, this)); + + this->postRenderConn = + _eventMgr.Connect(std::bind(&Implementation::OnPostRender, this)); + + this->renderTeardownConn = _eventMgr.Connect( + std::bind(&Implementation::OnRenderTeardown, this)); + + this->eventMgr = &_eventMgr; +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::DoPreUpdate( + const gz::sim::UpdateInfo &, gz::sim::EntityComponentManager & _ecm) +{ + _ecm.EachNew( + [&](const gz::sim::Entity & _entity, const gz::sim::components::Environment * _env) -> bool + { + if (_entity == gz::sim::worldEntity(_ecm)) + { + // \todo(anyone) Create an EnvironmentalData DOM class + // in sdformat and make gz-sensors and gz-sim use this + // generic data structure? Currently the data structure is + // duplicated in the two libraries. + auto envData = sensors::EnvironmentalData::MakeShared( + _env->Data()->frame, _env->Data()->reference, + static_cast(_env->Data()->units), + _env->Data()->staticTime); + + this->perStepRequests.push_back(requests::SetEnvironmentalData{envData}); + } + return true; + }); + + _ecm.EachNew( + [&]( + const gz::sim::Entity & _entity, const gz::sim::components::CustomSensor * _custom, + const gz::sim::components::ParentEntity * _parent) -> bool + { + using namespace gz::sim; + // Get sensor's scoped name without the world + std::string sensorScopedName = + removeParentScope(scopedName(_entity, _ecm, "::", false), "::"); + + // Check sensor's type before proceeding + sdf::Sensor sdf = _custom->Data(); + sdf::ElementPtr root = sdf.Element(); + if (!root->HasAttribute("gz:type")) + { + gzmsg << "No 'gz:type' attribute in custom sensor " + << "[" << sensorScopedName << "]. Ignoring." << std::endl; + return true; + } + auto type = root->Get("gz:type"); + if (type != "multibeam_sonar") + { + gzdbg << "Found custom sensor [" << sensorScopedName << "]" + << " of '" << type << "' type. Ignoring." << std::endl; + return true; + } + gzdbg << "Found custom sensor [" << sensorScopedName << "]" + << " of '" << type << "' type!" << std::endl; + + sdf.SetName(sensorScopedName); + + if (sdf.Topic().empty()) + { + // Default to scoped name as topic + sdf.SetTopic(scopedName(_entity, _ecm) + "/multibeam_sonar/velocity"); + } + + auto parentName = _ecm.Component(_parent->Data()); + + enableComponent(_ecm, _entity); + enableComponent(_ecm, _entity); + enableComponent(_ecm, _entity); + + this->perStepRequests.push_back( + requests::CreateSensor{sdf, _entity, _parent->Data(), parentName->Data()}); + + this->knownSensorEntities.insert(_entity); + return true; + }); +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::DoPostUpdate( + const gz::sim::UpdateInfo & _info, const gz::sim::EntityComponentManager & _ecm) +{ + _ecm.EachRemoved( + [&](const gz::sim::Entity & _entity, const gz::sim::components::CustomSensor *) + { + if (this->knownSensorEntities.count(_entity)) + { + this->perStepRequests.push_back(requests::DestroySensor{_entity}); + this->knownSensorEntities.erase(_entity); + } + return true; + }); + + std::lock_guard timeLock(this->timeMutex); + + if (!this->perStepRequests.empty() || (!_info.paused && this->nextUpdateTime <= _info.simTime)) + { + this->simTime = _info.simTime; + requests::SetWorldState request; + auto component = + _ecm.Component(gz::sim::worldEntity(_ecm)); + if (component) + { + request.worldState.origin = component->Data(); + } + + _ecm.Each< + gz::sim::components::WorldPose, gz::sim::components::WorldLinearVelocity, + gz::sim::components::WorldAngularVelocity>( + [&]( + const gz::sim::Entity & _entity, const gz::sim::components::WorldPose * _pose, + const gz::sim::components::WorldLinearVelocity * _linearVelocity, + const gz::sim::components::WorldAngularVelocity * _angularVelocity) + { + auto & kinematicState = request.worldState.kinematics[_entity]; + + kinematicState.pose = _pose->Data(); + kinematicState.linearVelocity = _linearVelocity->Data(); + kinematicState.angularVelocity = _angularVelocity->Data(); + return true; + }); + ; + + { + std::lock_guard lock(this->requestsMutex); + + this->queuedRequests.insert( + this->queuedRequests.end(), std::make_move_iterator(this->perStepRequests.begin()), + std::make_move_iterator(this->perStepRequests.end())); + this->perStepRequests.clear(); + + // keep a queue size of 1 for set world state + // this avoids setting the world state in gz-sensors multiple times + // before render update takes place + this->queuedSetWorldRequests.clear(); + this->queuedSetWorldRequests.push_back(std::move(request)); + } + + this->pendingRequests = true; + this->pendingSetWorldRequests = true; + + // this is a non-blocking call that force render to occur in the next + // render iteration in the render thread + this->eventMgr->Emit(); + } +} + +////////////////////////////////////////////////// +gz::rendering::VisualPtr MultibeamSonarSystem::Implementation::FindEntityVisual( + gz::rendering::ScenePtr _scene, gz::sim::Entity _entity) +{ + for (unsigned int i = 0; i < _scene->VisualCount(); ++i) + { + gz::rendering::VisualPtr visual = _scene->VisualByIndex(i); + if (visual->HasUserData("gazebo-entity")) + { + auto userData = visual->UserData("gazebo-entity"); + if (_entity == std::get(userData)) + { + return visual; + } + } + } + return gz::rendering::VisualPtr(); +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::Handle(requests::CreateSensor _request) +{ + auto * sensor = this->sensorManager.CreateSensor(_request.sdf); + if (nullptr == sensor) + { + gzerr << "Failed to create sensor " + << "[" << _request.sdf.Name() << "]" << std::endl; + return; + } + + sensor->SetEntity(_request.entity); + sensor->SetParent(_request.parentName); + + // Set the scene so it can create the rendering sensor + sensor->SetScene(this->scene); + sensor->SetManualSceneUpdate(true); + + if (this->latestWorldState) + { + sensor->SetWorldState(*this->latestWorldState); + } + + if (this->latestEnvironmentalData) + { + sensor->SetEnvironmentalData(*this->latestEnvironmentalData); + } + + gz::rendering::VisualPtr parentVisual = this->FindEntityVisual(this->scene, _request.parent); + if (!parentVisual) + { + gzerr << "Failed to find parent visual for sensor " + << "[" << _request.sdf.Name() << "]" << std::endl; + if (!this->sensorManager.Remove(sensor->Id())) + { + gzerr << "Internal error, missing sensor " + << "[" << _request.sdf.Name() << "]" << std::endl; + } + return; + } + for (auto renderingSensor : sensor->RenderingSensors()) + { + parentVisual->AddChild(renderingSensor); + } + + // Track sensor id for this sensor entity + this->sensorIdPerEntity.insert({_request.entity, sensor->Id()}); + + // Force (first) sensor update + this->needsUpdate = true; +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::Handle(requests::DestroySensor _request) +{ + auto it = this->sensorIdPerEntity.find(_request.entity); + if (it != this->sensorIdPerEntity.end()) + { + auto * sensor = + dynamic_cast(this->sensorManager.Sensor(it->second)); + if (sensor) + { + for (auto renderingSensor : sensor->RenderingSensors()) + { + renderingSensor->RemoveParent(); + } + this->sensorManager.Remove(it->second); + } + else + { + gzerr << "Internal error, missing DVL sensor for entity " + << "[" << _request.entity << "]" << std::endl; + } + this->sensorIdPerEntity.erase(it); + } +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::Handle(requests::SetWorldState _request) +{ + this->latestWorldState = std::move(_request.worldState); + for (const auto & [_, sensorId] : this->sensorIdPerEntity) + { + auto * sensor = + dynamic_cast(this->sensorManager.Sensor(sensorId)); + sensor->SetWorldState(*this->latestWorldState); + } + this->needsUpdate = true; +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::Handle(requests::SetEnvironmentalData _request) +{ + this->latestEnvironmentalData = std::move(_request.environmentalData); + for (const auto & [_, sensorId] : this->sensorIdPerEntity) + { + auto * sensor = + dynamic_cast(this->sensorManager.Sensor(sensorId)); + sensor->SetEnvironmentalData(*this->latestEnvironmentalData); + } + this->needsUpdate = true; +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::OnPreRender() +{ + GZ_PROFILE("MultibeamSonarSystem::Implementation::OnPreRender"); + + if (!this->scene) + { + this->scene = gz::rendering::sceneFromFirstRenderEngine(); + } + + if (this->pendingRequests.exchange(false)) + { + std::vector requests; + std::vector setWorldRequests; + { + std::lock_guard lock(this->requestsMutex); + requests.insert( + requests.end(), std::make_move_iterator(this->queuedRequests.begin()), + std::make_move_iterator(this->queuedRequests.end())); + this->queuedRequests.clear(); + setWorldRequests.insert( + setWorldRequests.end(), std::make_move_iterator(this->queuedSetWorldRequests.begin()), + std::make_move_iterator(this->queuedSetWorldRequests.end())); + this->queuedSetWorldRequests.clear(); + } + // handle requests - create/destroy sensor + for (auto & request : requests) + { + std::visit([this](auto & req) { this->Handle(std::move(req)); }, request); + } + // handle set world state requests + for (auto & request : setWorldRequests) + { + std::visit([this](auto & req) { this->Handle(std::move(req)); }, request); + } + } +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::OnRender() +{ + GZ_PROFILE("MultibeamSonarSystem::Implementation::OnRender"); + if (!this->scene->IsInitialized() || this->scene->SensorCount() == 0) + { + return; + } + + if (this->needsUpdate) + { + if (this->pendingSetWorldRequests.exchange(false)) + { + std::vector setWorldRequests; + { + std::lock_guard lock(this->requestsMutex); + setWorldRequests.insert( + setWorldRequests.end(), std::make_move_iterator(this->queuedSetWorldRequests.begin()), + std::make_move_iterator(this->queuedSetWorldRequests.end())); + this->queuedSetWorldRequests.clear(); + } + // handle set world state requests + for (auto & request : setWorldRequests) + { + std::visit([this](auto & req) { this->Handle(std::move(req)); }, request); + } + } + + auto closestUpdateTime = std::chrono::steady_clock::duration::max(); + + std::lock_guard timeLock(this->timeMutex); + + for (const auto & [_, sensorId] : this->sensorIdPerEntity) + { + gz::sensors::Sensor * sensor = this->sensorManager.Sensor(sensorId); + + constexpr bool kForce = true; + if (sensor->Update(this->simTime, !kForce)) + { + this->updatedSensorIds.push_back(sensorId); + } + + closestUpdateTime = std::min(sensor->NextDataUpdateTime(), closestUpdateTime); + } + this->nextUpdateTime = closestUpdateTime; + + this->needsUpdate = false; + } +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::OnPostRender() +{ + GZ_PROFILE("MultibeamSonarSystem::Implementation::OnPostRender"); + + std::lock_guard timeLock(this->timeMutex); + + for (const auto & sensorId : this->updatedSensorIds) + { + auto * sensor = + dynamic_cast(this->sensorManager.Sensor(sensorId)); + sensor->PostUpdate(this->simTime); + } + this->updatedSensorIds.clear(); +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Implementation::OnRenderTeardown() +{ + GZ_PROFILE("MultibeamSonarSystem::Implementation::OnRenderTeardown"); + for (const auto & [entityId, sensorId] : this->sensorIdPerEntity) + { + auto * sensor = + dynamic_cast(this->sensorManager.Sensor(sensorId)); + if (sensor) + { + for (auto renderingSensor : sensor->RenderingSensors()) + { + renderingSensor->RemoveParent(); + } + this->sensorManager.Remove(sensorId); + } + else + { + gzerr << "Internal error, missing DVL sensor for entity " + << "[" << entityId << "]" << std::endl; + } + } + this->sensorIdPerEntity.clear(); +} + +////////////////////////////////////////////////// +MultibeamSonarSystem::MultibeamSonarSystem() : dataPtr(gz::utils::MakeUniqueImpl()) +{ +} + +////////////////////////////////////////////////// +MultibeamSonarSystem::~MultibeamSonarSystem() {} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::Configure( + const gz::sim::Entity & _entity, const std::shared_ptr & _sdf, + gz::sim::EntityComponentManager & _ecm, gz::sim::EventManager & _eventMgr) +{ + GZ_PROFILE("MultibeamSonarSystem::Configure"); + this->dataPtr->DoConfigure(_entity, _sdf, _ecm, _eventMgr); +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::PreUpdate( + const gz::sim::UpdateInfo & _info, gz::sim::EntityComponentManager & _ecm) +{ + GZ_PROFILE("MultibeamSonarSystem::PreUpdate"); + this->dataPtr->DoPreUpdate(_info, _ecm); +} + +////////////////////////////////////////////////// +void MultibeamSonarSystem::PostUpdate( + const gz::sim::UpdateInfo & _info, const gz::sim::EntityComponentManager & _ecm) +{ + GZ_PROFILE("MultibeamSonarSystem::PostUpdate"); + this->dataPtr->DoPostUpdate(_info, _ecm); +} + +GZ_ADD_PLUGIN( + MultibeamSonarSystem, gz::sim::System, MultibeamSonarSystem::ISystemConfigure, + MultibeamSonarSystem::ISystemPreUpdate, MultibeamSonarSystem::ISystemPostUpdate) + +GZ_ADD_PLUGIN_ALIAS(MultibeamSonarSystem, "custom::MultibeamSonarSystem") \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/MultibeamSonarSystem.hh b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/MultibeamSonarSystem.hh new file mode 100644 index 00000000..486a5ff9 --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/MultibeamSonarSystem.hh @@ -0,0 +1,73 @@ +/* + * Copyright (C) 2022 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#ifndef GZ_SIM_SYSTEMS_MULTIBEAMSONARSYSTEM_HH_ +#define GZ_SIM_SYSTEMS_MULTIBEAMSONARSYSTEM_HH_ + +#include + +#include +#include "gz/sim/System.hh" + +namespace gz +{ +namespace sim +{ +// Inline bracket to help doxygen filtering +inline namespace GZ_SIM_VERSION_NAMESPACE +{ +namespace systems +{ + +/// \brief System that creates and updates MultibeamSonarSensor (DVL) sensors. +class MultibeamSonarSystem : public System, + public ISystemConfigure, + public ISystemPreUpdate, + public ISystemPostUpdate +{ + /// \brief Constructor +public: + explicit MultibeamSonarSystem(); + + /// \brief Destructor +public: + ~MultibeamSonarSystem(); + + // Documentation inherited +public: + void Configure( + const Entity & _entity, const std::shared_ptr & _sdf, + EntityComponentManager & _ecm, EventManager & _eventMgr) override; + + // Documentation inherited +public: + void PreUpdate(const UpdateInfo & _info, EntityComponentManager & _ecm) override; + + // Documentation inherited +public: + void PostUpdate(const UpdateInfo & _info, const EntityComponentManager & _ecm) override; + + /// \brief Pointer to private data + GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr) +}; + +} // namespace systems +} // namespace GZ_SIM_VERSION_NAMESPACE +} // namespace sim +} // namespace gz + +#endif \ No newline at end of file diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/hooks/multibeam_sonar_system.dsv.in b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/hooks/multibeam_sonar_system.dsv.in new file mode 100644 index 00000000..07f53dcf --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/hooks/multibeam_sonar_system.dsv.in @@ -0,0 +1,2 @@ +prepend-non-duplicate;GZ_SIM_SYSTEM_PLUGIN_PATH;lib/@PROJECT_NAME@/ +prepend-non-duplicate;LD_LIBRARY_PATH;lib/@PROJECT_NAME@/ diff --git a/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/package.xml b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/package.xml new file mode 100644 index 00000000..d8a5b9c9 --- /dev/null +++ b/gazebo/dave_gz_multibeam_sonar/multibeam_sonar_system/package.xml @@ -0,0 +1,24 @@ + + + multibeam_sonar_system + 0.0.1 + DAVE multibeam sonar sensor system + Woen-Sug Choi + Helena Moyen + Gaurav kumar + Apache 2.0 + geometry_msgs + ament_cmake + ament_lint_auto + + + ament_cmake + + \ No newline at end of file diff --git a/gazebo/dave_gz_sensor_plugins/include/dave_gz_sensor_plugins/sea_pressure_sensor.hh b/gazebo/dave_gz_sensor_plugins/include/dave_gz_sensor_plugins/sea_pressure_sensor.hh index d729f360..3b4ac670 100644 --- a/gazebo/dave_gz_sensor_plugins/include/dave_gz_sensor_plugins/sea_pressure_sensor.hh +++ b/gazebo/dave_gz_sensor_plugins/include/dave_gz_sensor_plugins/sea_pressure_sensor.hh @@ -1,5 +1,5 @@ -#ifndef dave_gz_sensor_plugins__SUBSEA_PRESSURE_SENSOR_HH_ -#define dave_gz_sensor_plugins__SUBSEA_PRESSURE_SENSOR_HH_ +#ifndef DAVE_GZ_SENSOR_PLUGINS__SUBSEA_PRESSURE_SENSOR_HH_ +#define DAVE_GZ_SENSOR_PLUGINS__SUBSEA_PRESSURE_SENSOR_HH_ #include #include diff --git a/gazebo/dave_gz_sensor_plugins/package.xml b/gazebo/dave_gz_sensor_plugins/package.xml index de9335f2..3e6f729b 100644 --- a/gazebo/dave_gz_sensor_plugins/package.xml +++ b/gazebo/dave_gz_sensor_plugins/package.xml @@ -12,6 +12,8 @@ ament_lint_auto dave_interfaces protobuf + protobuf dave_interfaces rclcpp diff --git a/models/dave_object_models/hooks/dave_object_models.dsv.in b/models/dave_object_models/hooks/dave_object_models.dsv.in index 346888c8..000c1b2d 100644 --- a/models/dave_object_models/hooks/dave_object_models.dsv.in +++ b/models/dave_object_models/hooks/dave_object_models.dsv.in @@ -1 +1 @@ -prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;@CMAKE_INSTALL_PREFIX@/share/@PROJECT_NAME@ +prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;@CMAKE_INSTALL_PREFIX@/share/@PROJECT_NAME@ \ No newline at end of file diff --git a/models/dave_robot_models/launch/upload_robot.launch.py b/models/dave_robot_models/launch/upload_robot.launch.py index b48b1b4b..284d66fb 100755 --- a/models/dave_robot_models/launch/upload_robot.launch.py +++ b/models/dave_robot_models/launch/upload_robot.launch.py @@ -23,9 +23,9 @@ def generate_launch_description(): x = LaunchConfiguration("x") y = LaunchConfiguration("y") z = LaunchConfiguration("z") - roll = LaunchConfiguration("roll") - pitch = LaunchConfiguration("pitch") - yaw = LaunchConfiguration("yaw") + roll = LaunchConfiguration("R") + pitch = LaunchConfiguration("P") + yaw = LaunchConfiguration("Y") use_ned_frame = LaunchConfiguration("use_ned_frame") args = [ @@ -60,17 +60,17 @@ def generate_launch_description(): description="Initial z position", ), DeclareLaunchArgument( - "roll", + "R", default_value="0.0", description="Initial roll", ), DeclareLaunchArgument( - "pitch", + "P", default_value="0.0", description="Initial pitch", ), DeclareLaunchArgument( - "yaw", + "Y", default_value="0.0", description="Initial yaw", ), diff --git a/models/dave_sensor_models/description/blueview_p900/model.config b/models/dave_sensor_models/description/blueview_p900/model.config new file mode 100644 index 00000000..e05d269f --- /dev/null +++ b/models/dave_sensor_models/description/blueview_p900/model.config @@ -0,0 +1,15 @@ + + + blueview_p900 + 1.0 + model.sdf + + + Brian Bingham + briansbingham@gmail.com + + + + Blueview P900 + + diff --git a/models/dave_sensor_models/description/blueview_p900/model.sdf b/models/dave_sensor_models/description/blueview_p900/model.sdf new file mode 100644 index 00000000..15c91ccf --- /dev/null +++ b/models/dave_sensor_models/description/blueview_p900/model.sdf @@ -0,0 +1,128 @@ + + + + 4 0 0.5 0 0.0 3.14 + + + 0 0 0 0 0 0 + 3.5 + + 0.0195872 + 0 + 0 + 0.0195872 + 0 + 0.0151357 + + + 1 + + + + + 1.047 + + 320 + 240 + + + 0.1 + 100 + + + 1 + 30 + true + /sensor/camera + + + + + 10 + /sensor/depth_camera + true + + 1.05 + + 320 + 240 + R_FLOAT32 + + + 0.1 + 10.0 + + + + + + + + + + true + 30.0 + /sensor/multibeam_sonar + true + + + + + 1024 + -0.78539816339 + 0.78539816339 + + + 10 + -0.349066 + 0.349066 + + + + 0.1 + 5.0 + + + + + + + 0 + 0 + 0 + + + 0 0 0 0 0 0 + + + 1 1 1 + model://meshes/blueview_p900/p900.dae + + + 0 + 1 + + + 0 0 0 0 0 0 + + + model://meshes/blueview_p900/COLLISION-p900.dae + + + + + 1 + 1 + + diff --git a/models/dave_sensor_models/meshes/blueview_p900/COLLISION-p900.dae b/models/dave_sensor_models/meshes/blueview_p900/COLLISION-p900.dae new file mode 100644 index 00000000..1a5cbd9f --- /dev/null +++ b/models/dave_sensor_models/meshes/blueview_p900/COLLISION-p900.dae @@ -0,0 +1,70 @@ + + + + + Blender User + Blender 2.82.7 commit date:2020-02-12, commit time:16:20, hash:77d23b0bd76f + + 2020-06-05T11:56:34 + 2020-06-05T11:56:34 + + Z_UP + + + + + + + + 0.05001103 0.0545004 0 -0.2101659 0.0545004 0 0.05001103 0.0534532 0.01063239 -0.2101659 0.0534532 0.01063239 0.05001103 0.05035179 0.02085626 -0.2101659 0.05035179 0.02085626 0.05001103 0.0453155 0.03027862 -0.2101659 0.0453155 0.03027862 0.05001103 0.03853768 0.03853738 -0.2101659 0.03853768 0.03853738 0.05001103 0.03027892 0.04531514 -0.2101659 0.03027892 0.0453152 0.05001103 0.02085655 0.0503515 -0.2101659 0.02085655 0.0503515 0.05001103 0.01063275 0.0534529 -0.2101659 0.01063275 0.0534529 0.05001103 3.05411e-7 0.0545001 -0.2101659 3.05411e-7 0.0545001 0.05001103 -0.01063209 0.0534529 -0.2101659 -0.01063209 0.0534529 0.05001103 -0.02085596 0.0503515 -0.2101659 -0.02085596 0.0503515 0.05001103 -0.03027832 0.04531514 -0.2101659 -0.03027832 0.0453152 0.05001103 -0.03853708 0.03853738 -0.2101659 -0.03853708 0.03853738 0.05001103 -0.0453149 0.03027862 -0.2101659 -0.0453149 0.03027862 0.05001103 -0.0503512 0.02085626 -0.2101659 -0.0503512 0.02085626 0.05001103 -0.05345261 0.01063239 -0.2101659 -0.05345261 0.01063239 0.05001103 -0.0544998 0 -0.2101659 -0.0544998 0 0.05001103 -0.05345261 -0.01063245 -0.2101659 -0.05345261 -0.01063245 0.05001103 -0.0503512 -0.02085632 -0.2101659 -0.0503512 -0.02085626 0.05001103 -0.04531484 -0.03027868 -0.2101659 -0.04531484 -0.03027868 0.05001103 -0.03853702 -0.03853744 -0.2101659 -0.03853702 -0.03853744 0.05001103 -0.03027826 -0.0453152 -0.2101659 -0.03027826 -0.0453152 0.05001103 -0.0208559 -0.05035156 -0.2101659 -0.0208559 -0.05035156 0.05001103 -0.01063209 -0.0534529 -0.2101659 -0.01063209 -0.0534529 0.05001103 3.53922e-7 -0.0545001 -0.2101659 3.53922e-7 -0.0545001 0.05001103 0.01063275 -0.0534529 -0.2101659 0.01063275 -0.0534529 0.05001103 0.02085661 -0.0503515 -0.2101659 0.02085661 -0.0503515 0.05001103 0.03027898 -0.04531514 -0.2101659 0.03027898 -0.04531514 0.05001103 0.03853774 -0.03853732 -0.2101659 0.03853774 -0.03853732 0.05001103 0.0453155 -0.03027856 -0.2101659 0.0453155 -0.03027856 0.05001103 0.05035185 -0.0208562 -0.2101659 0.05035185 -0.0208562 0.05001103 0.0534532 -0.01063233 -0.2101659 0.0534532 -0.01063233 + + + + + + + + + + 0 0.995185 0.09801512 0 0.9569402 0.2902855 0 0.8819226 0.4713945 0 0.7730104 0.6343933 0 0.6343933 0.7730106 0 0.4713944 0.8819225 0 0.2902858 0.95694 0 0.09801614 0.9951848 0 -0.0980162 0.9951848 0 -0.2902856 0.9569401 0 -0.4713943 0.8819226 0 -0.6343929 0.7730109 0 -0.7730104 0.6343933 0 -0.8819226 0.4713945 0 -0.9569401 0.2902859 0 -0.9951845 0.09801965 0 -0.9951847 -0.09801846 0 -0.9569404 -0.2902848 0 -0.8819212 -0.4713971 0 -0.7730101 -0.6343937 0 -0.634391 -0.7730125 0 -0.4713987 -0.8819202 0 -0.2902809 -0.9569415 0 -0.09801959 -0.9951845 0 0.09801954 -0.9951845 0 0.2902849 -0.9569403 0 0.4713984 -0.8819205 0 0.6343931 -0.7730107 0 0.7730104 -0.6343934 0 0.8819234 -0.4713929 -1 -4.70323e-7 0 0 0.9569413 -0.2902817 0 0.9951848 -0.0980165 1 0 0 0 0.9951849 0.09801578 0 0.9569403 0.2902848 0 0.8819227 0.471394 0 0.7730103 0.6343937 0 0.634393 0.7730109 0 0.4713944 0.8819225 0 0.2902855 0.9569401 0 0.09801614 0.9951848 0 -0.2902852 0.9569402 0 -0.4713944 0.8819225 0 -0.634393 0.7730109 0 -0.7730104 0.6343933 0 -0.8819227 0.471394 0 -0.9569404 0.2902846 0 -0.9951847 0.09801834 0 -0.9951845 -0.09801965 0 -0.95694 -0.2902861 0 -0.8819212 -0.4713968 0 -0.7730104 -0.6343933 0 -0.6343908 -0.7730125 0 -0.4713983 -0.8819205 0 -0.290281 -0.9569415 0 -0.09801995 -0.9951845 0 0.09801989 -0.9951845 0 0.2902851 -0.9569403 0 0.4713985 -0.8819204 0 0.6343932 -0.7730107 0 0.7730104 -0.6343933 0 0.881923 -0.4713935 -1 0 0 -1 -2.09114e-5 0 -1 -7.19913e-6 0 -1 -1.30696e-6 0 -1 0 0 -1 1.41214e-5 0 -1 -1.04554e-5 0 -1 1.04554e-5 0 -1 -3.92079e-6 0 -1 5.22772e-6 0 -1 -1.04554e-5 0 -1 2.09107e-5 0 -1 2.04558e-6 0 -1 1.88987e-6 0 -1 -2.69092e-6 0 -1 2.69092e-6 0 -1 7.56973e-7 0 0 0.9569413 -0.2902815 0 0.9951849 -0.09801584 1 -5.22787e-6 0 1 3.5304e-6 0 1 0 -1.4503e-7 1 -2.61387e-6 0 1 0 0 1 2.61387e-6 0 1 -1.79978e-6 -5.78029e-7 1 0 1.75185e-7 1 7.06077e-6 1.75185e-7 1 -2.61385e-6 0 1 -1.30688e-6 0 1 2.61388e-6 0 1 0 -8.49346e-7 1 0 6.67333e-7 1 0 0 1 1.89243e-7 -1.23874e-7 1 -1.89243e-7 0 1 0 0 + + + + + + + + + + 1 1 0.96875 0.5 1 0.5 0.96875 1 0.9375 0.5 0.96875 0.5 0.9375 1 0.90625 0.5 0.9375 0.5 0.90625 1 0.875 0.5 0.90625 0.5 0.875 1 0.84375 0.5 0.875 0.5 0.84375 1 0.8125 0.5 0.84375 0.5 0.8125 1 0.78125 0.5 0.8125 0.5 0.78125 1 0.75 0.5 0.78125 0.5 0.75 1 0.71875 0.5 0.75 0.5 0.71875 1 0.6875 0.5 0.71875 0.5 0.6875 1 0.65625 0.5 0.6875 0.5 0.65625 1 0.625 0.5 0.65625 0.5 0.625 1 0.59375 0.5 0.625 0.5 0.59375 1 0.5625 0.5 0.59375 0.5 0.5625 1 0.53125 0.5 0.5625 0.5 0.53125 1 0.5 0.5 0.53125 0.5 0.5 1 0.46875 0.5 0.5 0.5 0.46875 1 0.4375 0.5 0.46875 0.5 0.4375 1 0.40625 0.5 0.4375 0.5 0.40625 1 0.375 0.5 0.40625 0.5 0.375 1 0.34375 0.5 0.375 0.5 0.34375 1 0.3125 0.5 0.34375 0.5 0.3125 1 0.28125 0.5 0.3125 0.5 0.28125 1 0.25 0.5 0.28125 0.5 0.25 1 0.21875 0.5 0.25 0.5 0.21875 1 0.1875 0.5 0.21875 0.5 0.1875 1 0.15625 0.5 0.1875 0.5 0.15625 1 0.125 0.5 0.15625 0.5 0.125 1 0.09375 0.5 0.125 0.5 0.09375 1 0.0625 0.5 0.09375 0.5 0.341844 0.4717311 0.02826899 0.3418443 0.1581559 0.02826893 0.0625 1 0.03125 0.5 0.0625 0.5 0.03125 1 0 0.5 0.03125 0.5 0.9853885 0.2968217 0.7968216 0.01461148 0.5146115 0.2031785 1 1 0.96875 1 0.96875 0.5 0.96875 1 0.9375 1 0.9375 0.5 0.9375 1 0.90625 1 0.90625 0.5 0.90625 1 0.875 1 0.875 0.5 0.875 1 0.84375 1 0.84375 0.5 0.84375 1 0.8125 1 0.8125 0.5 0.8125 1 0.78125 1 0.78125 0.5 0.78125 1 0.75 1 0.75 0.5 0.75 1 0.71875 1 0.71875 0.5 0.71875 1 0.6875 1 0.6875 0.5 0.6875 1 0.65625 1 0.65625 0.5 0.65625 1 0.625 1 0.625 0.5 0.625 1 0.59375 1 0.59375 0.5 0.59375 1 0.5625 1 0.5625 0.5 0.5625 1 0.53125 1 0.53125 0.5 0.53125 1 0.5 1 0.5 0.5 0.5 1 0.46875 1 0.46875 0.5 0.46875 1 0.4375 1 0.4375 0.5 0.4375 1 0.40625 1 0.40625 0.5 0.40625 1 0.375 1 0.375 0.5 0.375 1 0.34375 1 0.34375 0.5 0.34375 1 0.3125 1 0.3125 0.5 0.3125 1 0.28125 1 0.28125 0.5 0.28125 1 0.25 1 0.25 0.5 0.25 1 0.21875 1 0.21875 0.5 0.21875 1 0.1875 1 0.1875 0.5 0.1875 1 0.15625 1 0.15625 0.5 0.15625 1 0.125 1 0.125 0.5 0.125 1 0.09375 1 0.09375 0.5 0.09375 1 0.0625 1 0.0625 0.5 0.341844 0.4717311 0.2968217 0.4853885 0.25 0.49 0.25 0.49 0.2031787 0.4853885 0.1581563 0.4717312 0.1581563 0.4717312 0.1166634 0.4495529 0.08029454 0.4197058 0.08029454 0.4197058 0.05044746 0.3833371 0.1581563 0.4717312 0.05044746 0.3833371 0.02826899 0.3418443 0.1581563 0.4717312 0.02826899 0.3418443 0.01461154 0.2968219 0.00999999 0.2500002 0.00999999 0.2500002 0.01461148 0.2031785 0.02826899 0.3418443 0.01461148 0.2031785 0.02826881 0.1581561 0.02826899 0.3418443 0.02826881 0.1581561 0.05044716 0.1166633 0.1581559 0.02826893 0.05044716 0.1166633 0.08029425 0.08029443 0.1581559 0.02826893 0.08029425 0.08029443 0.116663 0.05044734 0.1581559 0.02826893 0.1581559 0.02826893 0.2031782 0.01461154 0.2499999 0.00999999 0.2499999 0.00999999 0.2968216 0.01461148 0.1581559 0.02826893 0.2968216 0.01461148 0.341844 0.02826887 0.1581559 0.02826893 0.341844 0.02826887 0.3833369 0.05044728 0.4197056 0.08029437 0.4197056 0.08029437 0.4495527 0.1166631 0.4717311 0.158156 0.4717311 0.158156 0.4853885 0.2031783 0.49 0.25 0.49 0.25 0.4853885 0.2968217 0.4717311 0.341844 0.4717311 0.341844 0.4495527 0.3833369 0.4197056 0.4197056 0.4197056 0.4197056 0.3833369 0.4495527 0.341844 0.4717311 0.341844 0.4717311 0.25 0.49 0.02826899 0.3418443 0.25 0.49 0.1581563 0.4717312 0.02826899 0.3418443 0.341844 0.02826887 0.4197056 0.08029437 0.4717311 0.158156 0.4717311 0.158156 0.49 0.25 0.4717311 0.341844 0.4717311 0.341844 0.4197056 0.4197056 0.341844 0.4717311 0.02826899 0.3418443 0.02826881 0.1581561 0.1581559 0.02826893 0.1581559 0.02826893 0.341844 0.02826887 0.341844 0.4717311 0.341844 0.02826887 0.4717311 0.158156 0.341844 0.4717311 0.4717311 0.158156 0.4717311 0.341844 0.341844 0.4717311 0.0625 1 0.03125 1 0.03125 0.5 0.03125 1 0 1 0 0.5 0.7031787 0.4853885 0.75 0.49 0.7968217 0.4853885 0.7968217 0.4853885 0.841844 0.4717311 0.7031787 0.4853885 0.841844 0.4717311 0.8833369 0.4495527 0.7031787 0.4853885 0.8833369 0.4495527 0.9197056 0.4197056 0.9495527 0.3833369 0.9495527 0.3833369 0.9717311 0.341844 0.8833369 0.4495527 0.9717311 0.341844 0.9853885 0.2968217 0.8833369 0.4495527 0.9853885 0.2968217 0.99 0.25 0.9853885 0.2031783 0.9853885 0.2031783 0.9717311 0.158156 0.9853885 0.2968217 0.9717311 0.158156 0.9495527 0.1166631 0.9853885 0.2968217 0.9495527 0.1166631 0.9197056 0.08029437 0.8833369 0.05044728 0.8833369 0.05044728 0.841844 0.02826887 0.9495527 0.1166631 0.841844 0.02826887 0.7968216 0.01461148 0.9495527 0.1166631 0.7968216 0.01461148 0.75 0.00999999 0.7031782 0.01461154 0.7031782 0.01461154 0.6581559 0.02826893 0.7968216 0.01461148 0.6581559 0.02826893 0.616663 0.05044734 0.7968216 0.01461148 0.616663 0.05044734 0.5802943 0.08029443 0.5504472 0.1166633 0.5504472 0.1166633 0.5282688 0.1581561 0.5146115 0.2031785 0.5146115 0.2031785 0.51 0.2500002 0.5146116 0.2968219 0.5146116 0.2968219 0.5282691 0.3418443 0.5504475 0.3833371 0.5504475 0.3833371 0.5802946 0.4197058 0.6166634 0.4495529 0.6166634 0.4495529 0.6581563 0.4717312 0.5504475 0.3833371 0.6581563 0.4717312 0.7031787 0.4853885 0.5504475 0.3833371 0.616663 0.05044734 0.5504472 0.1166633 0.7968216 0.01461148 0.5504472 0.1166633 0.5146115 0.2031785 0.7968216 0.01461148 0.5146115 0.2031785 0.5146116 0.2968219 0.5504475 0.3833371 0.7031787 0.4853885 0.8833369 0.4495527 0.9853885 0.2968217 0.9853885 0.2968217 0.9495527 0.1166631 0.7968216 0.01461148 0.5146115 0.2031785 0.5504475 0.3833371 0.7031787 0.4853885 0.7031787 0.4853885 0.9853885 0.2968217 0.5146115 0.2031785 + + + + + + + + + + + + + + +

1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 29 14 42 30 14 43 28 14 44 31 15 45 32 15 46 30 15 47 33 16 48 34 16 49 32 16 50 35 17 51 36 17 52 34 17 53 37 18 54 38 18 55 36 18 56 39 19 57 40 19 58 38 19 59 41 20 60 42 20 61 40 20 62 43 21 63 44 21 64 42 21 65 45 22 66 46 22 67 44 22 68 47 23 69 48 23 70 46 23 71 49 24 72 50 24 73 48 24 74 51 25 75 52 25 76 50 25 77 53 26 78 54 26 79 52 26 80 55 27 81 56 27 82 54 27 83 57 28 84 58 28 85 56 28 86 59 29 87 60 29 88 58 29 89 5 30 90 53 30 91 37 30 92 61 31 93 62 31 94 60 31 95 63 32 96 0 32 97 62 32 98 14 33 99 30 33 100 46 33 101 1 34 102 3 34 103 2 34 104 3 35 105 5 35 106 4 35 107 5 36 108 7 36 109 6 36 110 7 37 111 9 37 112 8 37 113 9 38 114 11 38 115 10 38 116 11 39 117 13 39 118 12 39 119 13 40 120 15 40 121 14 40 122 15 41 123 17 41 124 16 41 125 17 8 126 19 8 127 18 8 128 19 42 129 21 42 130 20 42 131 21 43 132 23 43 133 22 43 134 23 44 135 25 44 136 24 44 137 25 45 138 27 45 139 26 45 140 27 46 141 29 46 142 28 46 143 29 47 144 31 47 145 30 47 146 31 48 147 33 48 148 32 48 149 33 49 150 35 49 151 34 49 152 35 50 153 37 50 154 36 50 155 37 51 156 39 51 157 38 51 158 39 52 159 41 52 160 40 52 161 41 53 162 43 53 163 42 53 164 43 54 165 45 54 166 44 54 167 45 55 168 47 55 169 46 55 170 47 56 171 49 56 172 48 56 173 49 57 174 51 57 175 50 57 176 51 58 177 53 58 178 52 58 179 53 59 180 55 59 181 54 59 182 55 60 183 57 60 184 56 60 185 57 61 186 59 61 187 58 61 188 59 62 189 61 62 190 60 62 191 5 63 192 3 63 193 1 63 194 1 64 195 63 64 196 61 64 197 61 63 198 59 63 199 57 63 200 57 63 201 55 63 202 61 63 203 55 65 204 53 65 205 61 65 206 53 66 207 51 66 208 49 66 209 49 63 210 47 63 211 53 63 212 47 67 213 45 67 214 53 67 215 45 63 216 43 63 217 37 63 218 43 63 219 41 63 220 37 63 221 41 63 222 39 63 223 37 63 224 37 63 225 35 63 226 33 63 227 33 68 228 31 68 229 37 68 230 31 63 231 29 63 232 37 63 233 29 69 234 27 69 235 25 69 236 25 70 237 23 70 238 21 70 239 21 71 240 19 71 241 17 71 242 17 72 243 15 72 244 13 72 245 13 73 246 11 73 247 9 73 248 9 74 249 7 74 250 5 74 251 5 75 252 1 75 253 53 75 254 1 76 255 61 76 256 53 76 257 29 77 258 25 77 259 21 77 260 21 63 261 17 63 262 13 63 263 13 78 264 9 78 265 5 78 266 53 79 267 45 79 268 37 79 269 37 63 270 29 63 271 5 63 272 29 63 273 21 63 274 5 63 275 21 63 276 13 63 277 5 63 278 61 80 279 63 80 280 62 80 281 63 81 282 1 81 283 0 81 284 62 82 285 0 82 286 2 82 287 2 83 288 4 83 289 62 83 290 4 84 291 6 84 292 62 84 293 6 85 294 8 85 295 10 85 296 10 86 297 12 86 298 6 86 299 12 86 300 14 86 301 6 86 302 14 86 303 16 86 304 18 86 305 18 86 306 20 86 307 14 86 308 20 86 309 22 86 310 14 86 311 22 87 312 24 87 313 26 87 314 26 86 315 28 86 316 22 86 317 28 88 318 30 88 319 22 88 320 30 89 321 32 89 322 34 89 323 34 90 324 36 90 325 30 90 326 36 86 327 38 86 328 30 86 329 38 91 330 40 91 331 42 91 332 42 92 333 44 92 334 46 92 335 46 86 336 48 86 337 50 86 338 50 86 339 52 86 340 54 86 341 54 93 342 56 93 343 58 93 344 58 94 345 60 94 346 54 94 347 60 95 348 62 95 349 54 95 350 38 86 351 42 86 352 30 86 353 42 86 354 46 86 355 30 86 356 46 86 357 50 86 358 54 86 359 62 96 360 6 96 361 14 96 362 14 97 363 22 97 364 30 97 365 46 98 366 54 98 367 62 98 368 62 99 369 14 99 370 46 99 371

+ + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + \ No newline at end of file diff --git a/models/dave_sensor_models/meshes/blueview_p900/p900.dae b/models/dave_sensor_models/meshes/blueview_p900/p900.dae new file mode 100644 index 00000000..164a80dc --- /dev/null +++ b/models/dave_sensor_models/meshes/blueview_p900/p900.dae @@ -0,0 +1,115 @@ + + + + + Blender User + Blender 2.82.7 commit date:2020-02-12, commit time:16:20, hash:77d23b0bd76f + + 2020-06-05T11:54:53 + 2020-06-05T11:54:53 + + Z_UP + + + + + + + tx-p900_png + + + + + tx-p900_png-surface + + + + + + 0 0 0 1 + + + + + + 1.45 + + + + + + + + + tx-p900.png + + + + + + + + + + + + -0.2101307 -0.0510078 0 -0.05533331 -0.0510078 0 -0.2101307 -0.05002766 -0.009951174 -0.05533325 -0.05002766 -0.009951174 -0.2101307 -0.04712498 -0.01951992 -0.05533331 -0.04712498 -0.01951992 -0.2101307 -0.04241132 -0.02833855 -0.05533337 -0.04241132 -0.02833861 -0.2101307 -0.03606778 -0.03606814 -0.05533331 -0.03606778 -0.03606814 -0.2101307 -0.02833825 -0.04241168 -0.05533337 -0.02833825 -0.04241168 -0.2101307 -0.01951956 -0.04712527 -0.05533337 -0.01951956 -0.04712527 -0.2101307 -0.009950816 -0.0500279 -0.05533337 -0.009950816 -0.0500279 -0.2101307 -0.009950876 0.05002796 -0.05533325 -0.009950876 0.05002802 -0.2101307 -0.01951962 0.04712527 -0.05533325 -0.01951962 0.04712527 -0.2101307 -0.02833831 0.04241162 -0.05533325 -0.02833831 0.04241162 -0.2101307 -0.03606784 0.03606808 -0.05533331 -0.03606784 0.03606808 -0.2101307 -0.04241138 0.02833855 -0.05533331 -0.04241138 0.02833855 -0.2101307 -0.04712498 0.01951986 -0.05533331 -0.04712498 0.01951986 -0.2101307 -0.0500276 0.009951114 -0.05533331 -0.0500276 0.009951114 0.04929697 -0.008154571 0.04099756 -0.05908697 -0.01246768 0.06268101 0.04929697 -0.01599609 0.0386188 -0.05908697 -0.02445662 0.05904424 0.04929697 -0.02322292 0.034756 -0.05908697 -0.03550565 0.05313843 0.04929697 -0.02955728 0.02955758 -0.05908697 -0.04519021 0.04519051 0.04929697 -0.03475576 0.02322322 -0.05908697 -0.05313813 0.03550595 0.04929697 -0.0386185 0.01599645 -0.05908697 -0.05904388 0.02445691 0.04929697 -0.0409972 0.008154869 -0.05908697 -0.06268072 0.01246798 0.04929697 -0.04180043 0 -0.05908697 -0.06390875 0 0.04929697 -0.0409972 -0.008154928 -0.05908697 -0.06268072 -0.01246803 0.04929697 -0.0386185 -0.01599645 -0.05908697 -0.05904388 -0.02445691 0.04929697 -0.0347557 -0.02322322 -0.05908697 -0.05313807 -0.03550595 0.04929697 -0.02955722 -0.02955758 -0.05908697 -0.04519015 -0.04519051 0.04929697 -0.02322286 -0.03475606 -0.05908697 -0.03550559 -0.05313843 0.04929697 -0.01599609 -0.03861886 -0.05908697 -0.02445656 -0.05904424 0.04929697 -0.008154571 -0.0409975 -0.05908697 -0.01246768 -0.06268101 -0.03454262 -0.01246768 0.06268101 -0.03454262 -0.02445662 0.05904424 -0.03454262 -0.03550565 0.05313843 -0.03454262 -0.04519021 0.04519051 -0.03454262 -0.05313813 0.03550595 -0.03454262 -0.05904388 0.02445691 -0.03454262 -0.06268072 0.01246798 -0.03454262 -0.06390875 0 -0.03454262 -0.06268072 -0.01246803 -0.03454262 -0.05904388 -0.02445691 -0.03454262 -0.05313807 -0.03550595 -0.03454262 -0.04519015 -0.04519051 -0.03454262 -0.03550559 -0.05313843 -0.03454262 -0.02445656 -0.05904424 -0.03454262 -0.01246768 -0.06268101 -0.03112775 -0.01241677 0.06242483 -0.03112775 -0.02435666 0.0588029 -0.03112775 -0.03536051 0.05292123 -0.03112775 -0.0450055 0.04500579 -0.03272432 -0.05292093 0.03536081 -0.03272432 -0.05880254 0.02435696 -0.03272432 -0.06242454 0.01241701 -0.03272432 -0.06364756 0 -0.03272432 -0.06242454 -0.01241707 -0.03272432 -0.05880254 -0.02435696 -0.03272432 -0.05292087 -0.03536081 -0.03272432 -0.04500544 -0.04500579 -0.03272432 -0.03536045 -0.05292123 -0.03272432 -0.0243566 -0.05880296 -0.03272432 -0.01241672 -0.06242483 0.01136666 -0.01218891 0.06127941 0.01136666 -0.02390974 0.05772393 0.01136666 -0.03471171 0.05195015 0.01136666 -0.04417967 0.04417997 0.01136666 -0.05194991 0.03471201 0.01136666 -0.05194979 -0.03471201 0.01136666 -0.04417961 -0.04417997 0.01136666 -0.03471165 -0.05195021 0.01136666 -0.02390968 -0.05772393 0.01136666 -0.01218885 -0.06127941 0.01040482 -0.04893016 0.03305745 0.01044899 -0.05453127 0.02258771 0.01044899 -0.05789017 0.01151508 0.01044899 -0.05902433 0 0.01044899 -0.05789017 -0.01151514 0.01044899 -0.05453127 -0.02258771 0.01040482 -0.0489301 -0.03305745 -0.02979969 -0.05550086 -0.02298933 -0.02979922 -0.0497691 -0.03367614 -0.02979969 -0.05891942 -0.01171988 -0.02979969 -0.06007379 0 -0.02979969 -0.05891942 0.01171982 -0.02979969 -0.05550086 0.02298933 -0.02979922 -0.04976916 0.0336762 0.03033185 -0.01100021 0.05530333 0.03033185 -0.02157795 0.05209457 0.03033185 -0.03132653 0.04688388 0.03033185 -0.03987115 0.03987145 0.03033185 -0.03987109 -0.03987145 0.03033185 -0.03132647 -0.04688394 0.03033185 -0.02157795 -0.05209463 0.03033185 -0.01100015 -0.05530333 0.02986413 -0.05104327 0.01966565 0.02986413 -0.05396759 0.01002544 0.02986413 -0.05495506 0 0.02986413 -0.05396759 -0.0100255 0.02986413 -0.05104327 -0.01966571 0.0298416 -0.04621958 -0.02868533 0.0298416 -0.04621964 0.02868533 0.02993398 -0.04352402 -0.03190547 0.03019553 -0.04518961 -0.03277558 0.03020977 -0.04518127 0.03277367 0.02992445 -0.04352879 0.03190636 -0.2101307 0.0510078 0 -0.05533331 0.0510078 0 -0.2101307 0.05002766 -0.009951174 -0.05533325 0.05002766 -0.009951174 -0.2101307 0.04712498 -0.01951992 -0.05533331 0.04712498 -0.01951992 -0.2101307 0.04241132 -0.02833855 -0.05533337 0.04241132 -0.02833861 -0.2101307 0.03606778 -0.03606814 -0.05533331 0.03606778 -0.03606814 -0.2101307 0.02833825 -0.04241168 -0.05533337 0.02833825 -0.04241168 -0.2101307 0.01951956 -0.04712527 -0.05533337 0.01951956 -0.04712527 -0.2101307 0.009950816 -0.0500279 -0.05533337 0.009950816 -0.0500279 -0.2101307 0 -0.05100804 -0.05533337 0 -0.05100804 -0.2101307 0 0.05100804 -0.05533325 0 0.05100804 -0.2101307 0.009950876 0.05002796 -0.05533325 0.009950876 0.05002802 -0.2101307 0.01951962 0.04712527 -0.05533325 0.01951962 0.04712527 -0.2101307 0.02833831 0.04241162 -0.05533325 0.02833831 0.04241162 -0.2101307 0.03606784 0.03606808 -0.05533331 0.03606784 0.03606808 -0.2101307 0.04241138 0.02833855 -0.05533331 0.04241138 0.02833855 -0.2101307 0.04712498 0.01951986 -0.05533331 0.04712498 0.01951986 -0.2101307 0.0500276 0.009951114 -0.05533331 0.0500276 0.009951114 0.04929697 0 0.04180067 -0.05908697 0 0.06390905 0.04929697 0.008154571 0.04099756 -0.05908697 0.01246768 0.06268101 0.04929697 0.01599609 0.0386188 -0.05908697 0.02445662 0.05904424 0.04929697 0.02322292 0.034756 -0.05908697 0.03550565 0.05313843 0.04929697 0.02955728 0.02955758 -0.05908697 0.04519021 0.04519051 0.04929697 0.03475576 0.02322322 -0.05908697 0.05313813 0.03550595 0.04929697 0.0386185 0.01599645 -0.05908697 0.05904388 0.02445691 0.04929697 0.0409972 0.008154869 -0.05908697 0.06268072 0.01246798 0.04929697 0.04180043 0 -0.05908697 0.06390875 0 0.04929697 0.0409972 -0.008154928 -0.05908697 0.06268072 -0.01246803 0.04929697 0.0386185 -0.01599645 -0.05908697 0.05904388 -0.02445691 0.04929697 0.0347557 -0.02322322 -0.05908697 0.05313807 -0.03550595 0.04929697 0.02955722 -0.02955758 -0.05908697 0.04519015 -0.04519051 0.04929697 0.02322286 -0.03475606 -0.05908697 0.03550559 -0.05313843 0.04929697 0.01599609 -0.03861886 -0.05908697 0.02445656 -0.05904424 0.04929697 0.008154571 -0.0409975 -0.05908697 0.01246768 -0.06268101 0.04929697 0 -0.04180067 -0.05908697 0 -0.06390899 -0.03454262 0 0.06390905 -0.03454262 0.01246768 0.06268101 -0.03454262 0.02445662 0.05904424 -0.03454262 0.03550565 0.05313843 -0.03454262 0.04519021 0.04519051 -0.03454262 0.05313813 0.03550595 -0.03454262 0.05904388 0.02445691 -0.03454262 0.06268072 0.01246798 -0.03454262 0.06390875 0 -0.03454262 0.06268072 -0.01246803 -0.03454262 0.05904388 -0.02445691 -0.03454262 0.05313807 -0.03550595 -0.03454262 0.04519015 -0.04519051 -0.03454262 0.03550559 -0.05313843 -0.03454262 0.02445656 -0.05904424 -0.03454262 0.01246768 -0.06268101 -0.03454262 0 -0.06390899 -0.03112775 0 0.0636478 -0.03112775 0.01241677 0.06242483 -0.03112775 0.02435666 0.0588029 -0.03112775 0.03536051 0.05292123 -0.03112775 0.0450055 0.04500579 -0.03272432 0.05292093 0.03536081 -0.03272432 0.05880254 0.02435696 -0.03272432 0.06242454 0.01241701 -0.03272432 0.06364756 0 -0.03272432 0.06242454 -0.01241707 -0.03272432 0.05880254 -0.02435696 -0.03272432 0.05292087 -0.03536081 -0.03272432 0.04500544 -0.04500579 -0.03272432 0.03536045 -0.05292123 -0.03272432 0.0243566 -0.05880296 -0.03272432 0.01241672 -0.06242483 -0.03272432 0 -0.06364774 0.01136666 0 0.06247991 0.01136666 0.01218891 0.06127941 0.01136666 0.02390974 0.05772393 0.01136666 0.03471171 0.05195015 0.01136666 0.04417967 0.04417997 0.01136666 0.05194991 0.03471201 0.01136666 0.05194979 -0.03471201 0.01136666 0.04417961 -0.04417997 0.01136666 0.03471165 -0.05195021 0.01136666 0.02390968 -0.05772393 0.01136666 0.01218885 -0.06127941 0.01136666 0 -0.06247991 0.01040482 0.04893016 0.03305745 0.01044899 0.05453127 0.02258771 0.01044899 0.05789017 0.01151508 0.01044899 0.05902433 0 0.01044899 0.05789017 -0.01151514 0.01044899 0.05453127 -0.02258771 0.01040482 0.0489301 -0.03305745 -0.02979969 0.05550086 -0.02298933 -0.02979922 0.0497691 -0.03367614 -0.02979969 0.05891942 -0.01171988 -0.02979969 0.06007379 0 -0.02979969 0.05891942 0.01171982 -0.02979969 0.05550086 0.02298933 -0.02979922 0.04976916 0.0336762 0.03033185 0 0.05638676 0.03033185 0.01100021 0.05530333 0.03033185 0.02157795 0.05209457 0.03033185 0.03132653 0.04688388 0.03033185 0.03987115 0.03987145 0.03033185 0.03987109 -0.03987145 0.03033185 0.03132647 -0.04688394 0.03033185 0.02157795 -0.05209463 0.03033185 0.01100015 -0.05530333 0.03033185 0 -0.0563867 0.02986413 0.05104327 0.01966565 0.02986413 0.05396759 0.01002544 0.02986413 0.05495506 0 0.02986413 0.05396759 -0.0100255 0.02986413 0.05104327 -0.01966571 0.0298416 0.04621958 -0.02868533 0.0298416 0.04621964 0.02868533 0.02993398 0.04352402 -0.03190547 0.03019553 0.04518961 -0.03277558 0.03020977 0.04518127 0.03277367 0.02992445 0.04352879 0.03190636 + + + + + + + + + + -0.6856992 -0.7138987 -0.1420046 0 -1 0 -0.6857035 -0.727881 0 0 -0.9238803 -0.3826816 0 -0.9807879 -0.1950772 -0.6856969 -0.6724823 -0.2785453 0 -0.8314677 -0.5555732 -0.6857035 -0.5147049 -0.5146744 -0.6857008 -0.6052222 -0.4043767 0 -0.5555732 -0.8314677 0 -0.7071068 -0.7071068 -0.6856969 -0.2785453 -0.6724823 -0.6857008 -0.4043767 -0.6052222 -0.6857022 -0.1419746 -0.7139018 0 -0.3826816 -0.9238803 -0.6857035 0 -0.727881 0 -0.1950772 -0.9807879 -0.6857022 -0.1419746 0.7139018 0 0 1 -0.6857035 0 0.727881 0 -0.3826816 0.9238803 0 -0.1950772 0.9807879 -0.6857008 -0.4043767 0.6052222 -0.6856969 -0.2785453 0.6724823 0 -0.7071068 0.7071068 0 -0.5555732 0.8314677 -0.6857008 -0.6052222 0.4043767 -0.6857035 -0.5146744 0.5147049 -0.6856969 -0.6724823 0.2785453 0 -0.8314677 0.5555732 -0.6856992 -0.7138987 0.1420046 0 -0.9238803 0.3826816 0 -0.9807879 0.1950772 0.05194371 0 0.9986501 0.1669095 -0.192332 0.9670314 0.1669076 0 0.9859725 0.05194407 -0.3821645 0.9226333 0.1669073 -0.3773038 0.9109248 0.05194449 -0.5548173 0.830349 0.166911 -0.5477637 0.8198144 0.03805691 -0.1949234 0.98008 0.05194431 -0.1948065 0.9794653 0.05075293 -0.7083134 0.7040712 0.1706021 -0.6988889 0.6945857 0.03805685 0 0.9992756 0.1662043 -0.9713771 -0.169714 0.03805768 -0.5551784 0.8308601 0.03805756 -0.3824073 0.9232098 0.2881934 -0.8638783 0.4131088 0.4506739 -0.8245926 0.3419653 0.3425214 -0.9132378 -0.2206261 0.03958344 -0.7081075 0.7049944 0.4820472 -0.8094547 0.3352814 0.4505177 -0.8756132 0.1741704 -0.6857143 -0.5146825 0.5146825 0.07095628 -0.8293799 0.554161 0.07095706 -0.9215573 0.3817034 0.4820564 -0.8593088 0.1709095 0.0709564 -0.9974794 0 0.48205 -0.8761438 0 0.07095652 -0.9783151 0.1945887 0.4505188 -0.892767 0 0.07095652 -0.9783151 -0.1945887 0.4820564 -0.8593088 -0.1709095 0.1658081 -0.9714713 0.1695619 0.08478164 -0.7045609 -0.7045609 0.1700838 -0.6989218 -0.6946796 0.07095706 -0.9215573 -0.3817034 0.4820472 -0.8094547 -0.3352814 0.1664224 -0.5478236 -0.8198738 0.07095628 -0.8293799 -0.554161 0.2888041 -0.8631771 -0.4141468 0.08478301 -0.5535619 -0.8284812 0.1664213 -0.3773397 -0.9109988 0.07095664 -0.7053245 -0.7053245 0.08478248 -0.3813076 -0.9205523 0.166419 -0.19236 -0.9671104 0.08478236 -0.1943769 -0.9772561 0.1664178 0 -0.9860554 0.07095628 -0.554161 -0.8293799 -0.6857143 -0.5146825 -0.5146825 0.07095706 -0.3817034 -0.9215573 0.0709564 0 -0.9974794 0.08478045 0 -0.9963997 0.07095652 -0.1945887 -0.9783151 0.4602894 -0.173196 -0.8707106 0.4602887 0 -0.8877694 0.4602897 -0.3397086 -0.8202021 0.460295 -0.4932255 -0.7381445 0.4598672 -0.6438691 -0.6115185 0.4269697 -0.8731057 0.2353368 0.1127666 -0.9438518 0.3105278 0.4505177 -0.8756132 -0.1741704 0.8796489 -0.3471536 0.3251188 0.4274184 -0.872904 -0.2352708 0.4235482 -0.8654386 -0.2676246 0.1127666 -0.9438518 -0.3105278 0.4506739 -0.8245926 -0.3419653 0.460295 -0.4932255 0.7381445 0.4597684 -0.6439199 0.6115393 0.460285 -0.3397356 0.8201935 0.4602894 -0.173196 0.8707106 0.4602887 0 0.8877694 0.8796489 -0.3471536 -0.3251188 0.1221986 -0.9160317 0.3820385 0.1171017 -0.9738332 0.1947727 0.1154245 -0.9933163 0 0.1171017 -0.9738332 -0.1947727 0.1221986 -0.9160317 -0.3820385 0.8656452 -0.4149078 -0.2801963 0.4242464 -0.8651257 0.2675307 0.3891186 -0.7685015 -0.5079295 0.3879002 -0.8527396 -0.3498122 0.3863977 -0.9049721 -0.1781073 0.3859152 -0.9225343 0 0.3863977 -0.9049721 0.1781073 0.3879002 -0.8527396 0.3498122 0.3892174 -0.7684854 0.507878 0.8656452 -0.4149078 0.2801963 0.3425214 -0.9132378 0.2206261 0.8686132 -0.4569978 -0.1914788 0.8861175 0 0.4634607 0.8861216 -0.09039753 0.4545512 0.88612 -0.1773461 0.428182 0.8861136 -0.2574872 0.385361 0.8861136 -0.2574872 -0.385361 0.88612 -0.1773461 -0.428182 0.8861216 -0.09039753 -0.4545512 0.8861175 0 -0.4634607 0.8686132 -0.4569978 0.1914788 0.870549 -0.4824413 0.0969277 0.8711784 -0.4909667 0 0.870549 -0.4824413 -0.0969277 0 1 0 -0.6856992 0.7138987 -0.1420046 -0.6857035 0.727881 0 0 0.9238803 -0.3826816 -0.685711 0.6724655 -0.278551 0 0.8314677 -0.5555732 -0.6857008 0.6052222 -0.4043767 -0.6857035 0.5147049 -0.5146744 0 0.5555732 -0.8314677 -0.6857008 0.4043767 -0.6052222 -0.6856969 0.2785453 -0.6724823 0 0.3826816 -0.9238803 -0.6856992 0.1420046 -0.7138987 0 0.1950772 -0.9807879 -0.6856992 0.1420046 0.7138987 0 0.3826816 0.9238803 -0.6856969 0.2785453 0.6724823 -0.6857008 0.4043767 0.6052222 0 0.7071068 0.7071068 -0.6857143 0.5146825 0.5146825 -0.6857008 0.6052222 0.4043767 0 0.8314677 0.5555732 -0.6856969 0.6724823 0.2785453 0 0.9238803 0.3826816 -0.6856992 0.7138987 0.1420046 0 0.9807879 0.1950772 0.1669095 0.192332 0.9670314 0.05194407 0.3821645 0.9226333 0.05194431 0.1948065 0.9794653 0.1669073 0.3773038 0.9109248 0.05194449 0.5548173 0.830349 0.03805691 0.1949234 0.98008 0.166911 0.5477637 0.8198144 0.05075293 0.7083134 0.7040712 0.1662043 0.9713771 -0.169714 0.1706021 0.6988889 0.6945857 0.03805768 0.5551784 0.8308601 0.03805756 0.3824073 0.9232098 0.2881934 0.8638783 0.4131088 0.4506739 0.8245926 0.3419653 0.4820472 0.8094547 0.3352814 0.03958344 0.7081075 0.7049944 0.4505177 0.8756132 0.1741704 0.4820564 0.8593088 0.1709095 0.07095628 0.8293799 0.554161 0.07095706 0.9215573 0.3817034 0.0709564 0.9974794 0 0.07095652 0.9783151 0.1945887 0.4505188 0.892767 0 0.48205 0.8761438 0 0.07095652 0.9783151 -0.1945887 0.1658081 0.9714713 0.1695619 0.08478164 0.7045609 -0.7045609 0.2888041 0.8631771 -0.4141468 0.4820564 0.8593088 -0.1709095 0.07095706 0.9215573 -0.3817034 0.1664224 0.5478236 -0.8198738 0.1700838 0.6989218 -0.6946796 0.4820472 0.8094547 -0.3352814 0.07095628 0.8293799 -0.554161 -0.6856969 0.6724823 -0.2785453 0.1664213 0.3773397 -0.9109988 0.08478301 0.5535619 -0.8284812 0.07095664 0.7053245 -0.7053245 0.166419 0.19236 -0.9671104 0.08478248 0.3813076 -0.9205523 0.08478236 0.1943769 -0.9772561 0.07095628 0.554161 -0.8293799 -0.6857143 0.5146825 -0.5146825 0.07095706 0.3817034 -0.9215573 0.07095652 0.1945887 -0.9783151 -0.6857022 0.1419746 -0.7139018 0.4602894 0.173196 -0.8707106 0.4602897 0.3397086 -0.8202021 0.460295 0.4932255 -0.7381445 0.4598672 0.6438691 -0.6115185 0.1127666 0.9438518 0.3105278 0.4269697 0.8731057 0.2353368 0.4505177 0.8756132 -0.1741704 0.8796489 0.3471536 0.3251188 0.4235482 0.8654386 -0.2676246 0.4274184 0.872904 -0.2352708 0.3425214 0.9132378 -0.2206261 0.4506739 0.8245926 -0.3419653 0.460295 0.4932255 0.7381445 0.460285 0.3397356 0.8201935 0.4602894 0.173196 0.8707106 0.8796489 0.3471536 -0.3251188 0.1127666 0.9438518 -0.3105278 0.1171017 0.9738332 0.1947727 0.1221986 0.9160317 0.3820385 0.1154245 0.9933163 0 0.1171017 0.9738332 -0.1947727 0.1221986 0.9160317 -0.3820385 0.8656452 0.4149078 -0.2801963 0.4242464 0.8651257 0.2675307 0.3891186 0.7685015 -0.5079295 0.3879002 0.8527396 -0.3498122 0.3863977 0.9049721 -0.1781073 0.3859152 0.9225343 0 0.3863977 0.9049721 0.1781073 0.3879002 0.8527396 0.3498122 0.3892174 0.7684854 0.507878 0.8656452 0.4149078 0.2801963 0.3425214 0.9132378 0.2206261 0.870549 0.4824413 0.0969277 0.8861136 0.2574872 0.385361 0.8861216 0.09039753 0.4545512 0.88612 0.1773461 0.428182 0.8861136 0.2574872 -0.385361 0.88612 0.1773461 -0.428182 0.8861216 0.09039753 -0.4545512 0.8686132 0.4569978 0.1914788 0.8711784 0.4909667 0 0.870549 0.4824413 -0.0969277 0.8686132 0.4569978 -0.1914788 0.4597684 0.6439199 0.6115393 0 0 -1 -0.6856992 -0.1420046 0.7138987 0 0.9807879 -0.1950772 0 0.7071068 -0.7071068 0 0.1950772 0.9807879 0 0.5555732 0.8314677 + + + + + + + + + + 0.672208 1.88749e-4 0.645327 0.3725346 0.6453271 1.88749e-4 0.672208 1.88749e-4 0.6990889 0.3725346 0.672208 0.3725346 0.6990889 1.88749e-4 0.7259699 0.3725346 0.6990889 0.3725346 0.7528508 1.88749e-4 0.7259699 0.3725346 0.7259699 1.88749e-4 0.7528508 1.88749e-4 0.7797316 0.3725346 0.7528508 0.3725346 0.8066125 1.88749e-4 0.7797316 0.3725346 0.7797317 1.88749e-4 0.8334933 1.88749e-4 0.8066125 0.3725346 0.8066125 1.88749e-4 0.8603732 1.88749e-4 0.8334932 0.3725346 0.8334933 1.88749e-4 0.457161 1.88693e-4 0.4302809 0.3725345 0.4302809 1.88693e-4 0.457161 1.88693e-4 0.4840418 0.3725345 0.457161 0.3725345 0.5109227 1.88693e-4 0.4840418 0.3725345 0.4840418 1.88693e-4 0.5109227 1.88693e-4 0.5378035 0.3725345 0.5109227 0.3725345 0.5646844 1.88693e-4 0.5378035 0.3725345 0.5378035 1.88693e-4 0.5915654 1.88749e-4 0.5646845 0.3725345 0.5646844 1.88693e-4 0.6184463 1.88749e-4 0.5915654 0.3725346 0.5915654 1.88749e-4 0.6453271 1.88749e-4 0.6184463 0.3725346 0.6184463 1.88749e-4 0.3708247 0.7051678 0.3708238 0.9056983 0.3240271 0.8181468 0.4597869 0.4413655 0.4885111 0.5454056 0.4597868 0.5454056 0.4885111 0.5454056 0.517236 0.4413655 0.517236 0.5454056 0.517236 0.5454056 0.5459611 0.4413655 0.545961 0.5454056 0.4597869 0.4413655 0.4885111 0.4330044 0.4885111 0.4413655 0.545961 0.5454056 0.5746859 0.4413655 0.5746859 0.5454056 0.4885111 0.4330044 0.517236 0.4413655 0.4885111 0.4413655 0.4597869 0.3729119 0.4885111 0.4330044 0.4597869 0.4330044 0.5746859 0.4413655 0.6034109 0.5454056 0.5746859 0.5454056 0.517236 0.4413655 0.5459611 0.4330044 0.5459611 0.4413655 0.4885111 0.4330044 0.517236 0.3729119 0.517236 0.4330044 0.603411 0.4374563 0.6321359 0.4446169 0.6025581 0.4446181 0.5459611 0.4413655 0.5746859 0.4330044 0.5746859 0.4413655 0.517236 0.4330044 0.545961 0.3729119 0.5459611 0.4330044 0.6321359 0.4374563 0.660861 0.4446169 0.6321359 0.4446169 0.5746859 0.4330044 0.603411 0.4374563 0.5746859 0.4413655 0.5459611 0.4330044 0.5746859 0.3729119 0.5746859 0.4330044 0.603411 0.4330044 0.6321359 0.4374563 0.603411 0.4374563 0.5746859 0.3729119 0.603411 0.4330044 0.5746859 0.4330044 0.6321359 0.4330045 0.660861 0.4374563 0.6321359 0.4374563 0.603411 0.3729119 0.6321359 0.4330045 0.603411 0.4330044 0.660861 0.4374563 0.689586 0.4330045 0.689586 0.4374563 0.6321359 0.4330045 0.660861 0.372912 0.660861 0.4330045 0.660861 0.4374563 0.689586 0.4446169 0.660861 0.4446169 0.689586 0.4374563 0.718311 0.4330045 0.718311 0.4374563 0.660861 0.4330045 0.6895861 0.372912 0.689586 0.4330045 0.7757611 0.5454056 0.8044861 0.4374563 0.8044861 0.5454057 0.718311 0.4374563 0.7470361 0.4330045 0.7470361 0.4374563 0.689586 0.4330045 0.7183111 0.372912 0.718311 0.4330045 0.8044861 0.4374563 0.8332111 0.5454057 0.8044861 0.5454057 0.7470361 0.4374563 0.7757611 0.4330045 0.7757611 0.4374563 0.718311 0.4330045 0.7470361 0.372912 0.7470361 0.4330045 0.8332111 0.4374563 0.861936 0.5454057 0.8332111 0.5454057 0.7757611 0.4374563 0.8044861 0.4330045 0.8044861 0.4374563 0.7470361 0.372912 0.7757611 0.4330045 0.7470361 0.4330045 0.861936 0.4374563 0.890661 0.5454057 0.861936 0.5454057 0.8044861 0.4330045 0.8332111 0.4374563 0.8044861 0.4374563 0.7757611 0.372912 0.8044861 0.4330045 0.7757611 0.4330045 0.890661 0.4374563 0.9193851 0.5454056 0.890661 0.5454057 0.8332111 0.4330045 0.861936 0.4374563 0.8332111 0.4374563 0.8044862 0.372912 0.8332111 0.4330045 0.8044861 0.4330045 0.861936 0.4330045 0.890661 0.4374563 0.861936 0.4374563 0.8332111 0.372912 0.861936 0.4330045 0.8332111 0.4330045 0.890661 0.4374563 0.9193851 0.4330045 0.9193851 0.4374563 0.861936 0.372912 0.890661 0.4330045 0.861936 0.4330045 0.890661 0.372912 0.9193851 0.4330045 0.890661 0.4330045 0.890661 0.6026103 0.9193851 0.5454056 0.9193851 0.6026103 0.8619362 0.6026103 0.890661 0.5454057 0.890661 0.6026103 0.8332111 0.5454057 0.8619362 0.6026103 0.8332112 0.6026103 0.8044861 0.5454057 0.8332112 0.6026103 0.8044862 0.6026103 0.718311 0.4374563 0.689586 0.4446169 0.689586 0.4374563 0.7813857 0.6022767 0.7765093 0.5430507 0.7757611 0.5454056 0.7470361 0.4374563 0.718311 0.4446169 0.718311 0.4374563 0.5746858 0.6759727 0.5977775 0.6023113 0.5970505 0.6016129 0.6034109 0.5454056 0.6025581 0.4446181 0.6026628 0.5430507 0.7757611 0.4374563 0.7470361 0.4446169 0.7470361 0.4374563 0.5459609 0.6026102 0.5746859 0.5454056 0.5746859 0.6026102 0.517236 0.6026102 0.545961 0.5454056 0.5459609 0.6026102 0.488511 0.6026102 0.517236 0.5454056 0.517236 0.6026102 0.4597868 0.6026102 0.4885111 0.5454056 0.488511 0.6026102 0.5977775 0.6023113 0.5746859 0.5454056 0.6034109 0.5454056 0.8044864 0.6759727 0.7813857 0.6022767 0.8044862 0.6026103 0.6026628 0.5430507 0.6321359 0.4446169 0.6321358 0.5431588 0.6321359 0.4446169 0.660861 0.5431588 0.6321358 0.5431588 0.660861 0.5431588 0.689586 0.4446169 0.689586 0.5431588 0.689586 0.5431588 0.718311 0.4446169 0.7183111 0.5431588 0.7183111 0.5431588 0.7470361 0.4446169 0.7470361 0.5431588 0.7470361 0.4446169 0.7765093 0.5430507 0.7470361 0.5431588 0.7757613 0.6759727 0.7821273 0.6016363 0.8044864 0.6759727 0.7470361 0.5431588 0.7708455 0.6014099 0.7433856 0.6014651 0.7183111 0.5431588 0.7433856 0.6014651 0.7164566 0.6014651 0.689586 0.5431588 0.7164566 0.6014651 0.6895861 0.6014651 0.6627154 0.6014651 0.689586 0.5431588 0.6895861 0.6014651 0.6357864 0.6014651 0.660861 0.5431588 0.6627154 0.6014651 0.6083264 0.6014101 0.6321358 0.5431588 0.6357864 0.6014651 0.5970505 0.6016129 0.6034107 0.6759727 0.5746858 0.6759727 0.7757611 0.5454056 0.7766139 0.4446181 0.7757611 0.4374563 0.6574972 0.6804152 0.6987715 0.6763501 0.6061853 0.8495649 0.05882138 0.9637051 1.8886e-4 0.8540101 0.03629517 0.7349835 0.4597868 0.6026102 0.4885107 0.6759727 0.4597868 0.6759727 0.4885107 0.6759727 0.517236 0.6026102 0.5172358 0.6759727 0.517236 0.6026102 0.5459607 0.6759727 0.5172358 0.6759727 0.5459609 0.6026102 0.5746858 0.6759727 0.5459607 0.6759727 0.8044862 0.6026103 0.8332114 0.6759727 0.8044864 0.6759727 0.8332112 0.6026103 0.8619363 0.6759727 0.8332114 0.6759727 0.8619363 0.6759727 0.890661 0.6026103 0.8906613 0.6759727 0.8906613 0.6759727 0.9193851 0.6026103 0.919385 0.6759727 0.6083264 0.6014101 0.6321358 0.6759727 0.6034107 0.6759727 0.6357864 0.6014651 0.660861 0.6759727 0.6321358 0.6759727 0.6627154 0.6014651 0.6895861 0.6759727 0.660861 0.6759727 0.6895861 0.6759727 0.7164566 0.6014651 0.7183111 0.6759727 0.7183111 0.6759727 0.7433856 0.6014651 0.7470363 0.6759727 0.7470363 0.6759727 0.7708455 0.6014099 0.7757613 0.6759727 0.7813857 0.6022767 0.8044861 0.5454057 0.8044862 0.6026103 0.7821273 0.6016363 0.7708455 0.6014099 0.7765093 0.5430507 0.7821273 0.6016363 0.7813857 0.6022767 0.8044864 0.6759727 0.5977775 0.6023113 0.6026628 0.5430507 0.5970505 0.6016129 0.5746859 0.6026102 0.5977775 0.6023113 0.5746858 0.6759727 0.6083264 0.6014101 0.5970505 0.6016129 0.6026628 0.5430507 0.2152348 0.3725345 0.1883539 1.88693e-4 0.2152348 1.88693e-4 0.1883539 1.88693e-4 0.161473 0.3725345 0.161473 1.88693e-4 0.161473 1.88693e-4 0.1345919 0.3725345 0.1345921 1.88693e-4 0.1345919 0.3725345 0.1077111 1.88693e-4 0.1345921 1.88693e-4 0.1077111 1.88693e-4 0.08083033 0.3725345 0.08083033 1.88693e-4 0.08083033 0.3725345 0.05394941 1.88693e-4 0.08083033 1.88693e-4 0.05394941 0.3725345 0.02706861 1.88693e-4 0.05394941 1.88693e-4 0.02706861 0.3725345 1.88693e-4 1.88693e-4 0.02706861 1.88693e-4 0.4302809 0.3725345 0.4034009 1.88693e-4 0.4302809 1.88693e-4 0.4034009 1.88693e-4 0.3765201 0.3725345 0.3765201 1.88693e-4 0.3765201 0.3725345 0.3496392 1.88693e-4 0.3765201 1.88693e-4 0.3496392 1.88693e-4 0.3227583 0.3725345 0.3227583 1.88693e-4 0.3227583 0.3725345 0.2958775 1.88693e-4 0.3227583 1.88693e-4 0.2958775 0.3725345 0.2689966 1.88693e-4 0.2958775 1.88693e-4 0.2689965 0.3725345 0.2421156 1.88693e-4 0.2689966 1.88693e-4 0.2421156 0.3725345 0.2152348 1.88693e-4 0.2421156 1.88693e-4 0.5353949 0.9056982 0.5353958 0.7051676 0.5821925 0.7927193 0.4310627 0.5454056 0.4597869 0.4413655 0.4597868 0.5454056 0.4310627 0.5454056 0.4023378 0.4413655 0.4310626 0.4413655 0.4023378 0.5454056 0.3736127 0.4413655 0.4023378 0.4413655 0.4597869 0.4413655 0.4310626 0.4330044 0.4597869 0.4330044 0.3736127 0.5454056 0.3448879 0.4413655 0.3736127 0.4413655 0.4023378 0.4413655 0.4310626 0.4330044 0.4310626 0.4413655 0.4310626 0.4330044 0.4597869 0.3729119 0.4597869 0.4330044 0.3161628 0.5454056 0.3448879 0.4413655 0.3448879 0.5454056 0.4023378 0.4413655 0.3736127 0.4330044 0.4023378 0.4330044 0.4310626 0.4330044 0.4023378 0.3729119 0.4310626 0.3729119 0.3161628 0.4374563 0.2874379 0.4446169 0.2874379 0.4374563 0.3736127 0.4413655 0.3448879 0.4330044 0.3736127 0.4330044 0.4023378 0.4330044 0.3736128 0.3729119 0.4023378 0.3729119 0.2874379 0.4374563 0.2587127 0.4446169 0.2587128 0.4374563 0.3161628 0.4374563 0.3448879 0.4330044 0.3448879 0.4413655 0.3736127 0.4330044 0.3448879 0.3729119 0.3736128 0.3729119 0.2874379 0.4374563 0.3161628 0.4330044 0.3161628 0.4374563 0.3161628 0.4330044 0.3448879 0.3729119 0.3448879 0.4330044 0.2587128 0.4374563 0.2874379 0.4330044 0.2874379 0.4374563 0.2874379 0.4330044 0.3161628 0.3729119 0.3161628 0.4330044 0.2587128 0.4374563 0.2299878 0.4330044 0.2587128 0.4330044 0.2874379 0.4330044 0.2587128 0.3729119 0.2874379 0.3729119 0.2587128 0.4374563 0.2299878 0.4446169 0.2299878 0.4374563 0.2299878 0.4374563 0.2012628 0.4330044 0.2299878 0.4330044 0.2587128 0.4330044 0.2299878 0.3729119 0.2587128 0.3729119 0.1438127 0.5454056 0.1150878 0.4374563 0.1438126 0.4374563 0.2012628 0.4374563 0.1725376 0.4330044 0.2012628 0.4330044 0.2299878 0.4330044 0.2012627 0.3729119 0.2299878 0.3729119 0.08636265 0.5454056 0.1150878 0.4374563 0.1150878 0.5454056 0.1725376 0.4374563 0.1438126 0.4330044 0.1725376 0.4330044 0.2012628 0.4330044 0.1725378 0.3729119 0.2012627 0.3729119 0.05763763 0.5454056 0.08636265 0.4374563 0.08636265 0.5454056 0.1438126 0.4374563 0.1150878 0.4330044 0.1438126 0.4330044 0.1438126 0.4330044 0.1725378 0.3729119 0.1725376 0.4330044 0.02891278 0.5454056 0.05763775 0.4374563 0.05763763 0.5454056 0.08636265 0.4374563 0.1150878 0.4330044 0.1150878 0.4374563 0.1150878 0.4330044 0.1438127 0.3729119 0.1438126 0.4330044 1.88749e-4 0.5454055 0.02891278 0.4374563 0.02891278 0.5454056 0.05763775 0.4374563 0.08636265 0.4330044 0.08636265 0.4374563 0.08636265 0.4330044 0.1150876 0.3729119 0.1150878 0.4330044 0.02891278 0.4374563 0.05763775 0.4330044 0.05763775 0.4374563 0.05763775 0.4330044 0.08636265 0.3729119 0.08636265 0.4330044 0.02891278 0.4374563 1.88749e-4 0.4330044 0.02891278 0.4330044 0.02891278 0.4330044 0.05763775 0.3729119 0.05763775 0.4330044 1.88749e-4 0.4330044 0.0289129 0.3729119 0.02891278 0.4330044 0.02891266 0.6026102 1.88749e-4 0.5454055 0.02891278 0.5454056 0.05763763 0.6026102 0.02891278 0.5454056 0.05763763 0.5454056 0.05763763 0.6026102 0.08636265 0.5454056 0.08636254 0.6026102 0.08636254 0.6026102 0.1150878 0.5454056 0.1150875 0.6026102 0.2299878 0.4446169 0.2012628 0.4374563 0.2299878 0.4374563 0.1430646 0.5430507 0.1381881 0.6022766 0.1438127 0.5454056 0.2012628 0.4446169 0.1725376 0.4374563 0.2012628 0.4374563 0.3448881 0.6759727 0.3225233 0.6016129 0.3217962 0.6023113 0.3161628 0.5454056 0.3170157 0.4446181 0.3161628 0.4374563 0.1725376 0.4446169 0.1438126 0.4374563 0.1725376 0.4374563 0.3736128 0.6026102 0.3448879 0.5454056 0.3736127 0.5454056 0.4023379 0.6026102 0.3736127 0.5454056 0.4023378 0.5454056 0.4310628 0.6026102 0.4023378 0.5454056 0.4310627 0.5454056 0.4597868 0.6026102 0.4310627 0.5454056 0.4597868 0.5454056 0.3448879 0.5454056 0.3217962 0.6023113 0.3161628 0.5454056 0.1150874 0.6759727 0.1150875 0.6026102 0.1381881 0.6022766 0.3169111 0.5430507 0.2874379 0.4446169 0.3170157 0.4446181 0.2587128 0.5431588 0.2874379 0.4446169 0.2874379 0.5431588 0.2587128 0.5431588 0.2299878 0.4446169 0.2587127 0.4446169 0.2299878 0.5431588 0.2012628 0.4446169 0.2299878 0.4446169 0.2012627 0.5431588 0.1725376 0.4446169 0.2012628 0.4446169 0.1430646 0.5430507 0.1725376 0.4446169 0.1725376 0.5431588 0.1438124 0.6759727 0.1374465 0.6016363 0.1487283 0.6014099 0.1487283 0.6014099 0.1725376 0.5431588 0.1761882 0.6014651 0.1761882 0.6014651 0.2012627 0.5431588 0.2031171 0.6014651 0.2031171 0.6014651 0.2299878 0.5431588 0.2299878 0.6014651 0.2568583 0.6014651 0.2299878 0.5431588 0.2587128 0.5431588 0.2837874 0.6014651 0.2587128 0.5431588 0.2874379 0.5431588 0.3112474 0.60141 0.2874379 0.5431588 0.3169111 0.5430507 0.316163 0.6759727 0.3225233 0.6016129 0.3448881 0.6759727 0.1429599 0.4446181 0.1438127 0.5454056 0.1438126 0.4374563 0.7900693 0.8129873 0.7384586 0.8758753 0.6574959 0.8838493 0.2875431 0.7349833 0.2650157 0.9637054 0.1459888 0.9998114 0.431063 0.6759727 0.4597868 0.6026102 0.4597868 0.6759727 0.431063 0.6759727 0.4023379 0.6026102 0.4310628 0.6026102 0.3736129 0.6759727 0.4023379 0.6026102 0.402338 0.6759727 0.3448881 0.6759727 0.3736128 0.6026102 0.3736129 0.6759727 0.0863623 0.6759727 0.1150875 0.6026102 0.1150874 0.6759727 0.05763733 0.6759727 0.08636254 0.6026102 0.0863623 0.6759727 0.05763733 0.6759727 0.02891266 0.6026102 0.05763763 0.6026102 0.02891236 0.6759727 1.88749e-4 0.6026102 0.02891266 0.6026102 0.287438 0.6759727 0.3112474 0.60141 0.316163 0.6759727 0.2587128 0.6759727 0.2837874 0.6014651 0.287438 0.6759727 0.2299877 0.6759727 0.2568583 0.6014651 0.2587128 0.6759727 0.2299877 0.6759727 0.2031171 0.6014651 0.2299878 0.6014651 0.2012627 0.6759727 0.1761882 0.6014651 0.2031171 0.6014651 0.1725375 0.6759727 0.1487283 0.6014099 0.1761882 0.6014651 0.1150878 0.5454056 0.1381881 0.6022766 0.1150875 0.6026102 0.1374465 0.6016363 0.1430646 0.5430507 0.1487283 0.6014099 0.1374465 0.6016363 0.1150874 0.6759727 0.1381881 0.6022766 0.3169111 0.5430507 0.3217962 0.6023113 0.3225233 0.6016129 0.3448879 0.6026102 0.3448881 0.6759727 0.3217962 0.6023113 0.3112474 0.60141 0.3169111 0.5430507 0.3225233 0.6016129 0.672208 1.88749e-4 0.672208 0.3725346 0.645327 0.3725346 0.672208 1.88749e-4 0.6990889 1.88749e-4 0.6990889 0.3725346 0.6990889 1.88749e-4 0.7259699 1.88749e-4 0.7259699 0.3725346 0.7528508 1.88749e-4 0.7528508 0.3725346 0.7259699 0.3725346 0.7528508 1.88749e-4 0.7797317 1.88749e-4 0.7797316 0.3725346 0.8066125 1.88749e-4 0.8066125 0.3725346 0.7797316 0.3725346 0.8334933 1.88749e-4 0.8334932 0.3725346 0.8066125 0.3725346 0.8603732 1.88749e-4 0.8603731 0.3725346 0.8334932 0.3725346 0.457161 1.88693e-4 0.457161 0.3725345 0.4302809 0.3725345 0.457161 1.88693e-4 0.4840418 1.88693e-4 0.4840418 0.3725345 0.5109227 1.88693e-4 0.5109227 0.3725345 0.4840418 0.3725345 0.5109227 1.88693e-4 0.5378035 1.88693e-4 0.5378035 0.3725345 0.5646844 1.88693e-4 0.5646845 0.3725345 0.5378035 0.3725345 0.5915654 1.88749e-4 0.5915654 0.3725346 0.5646845 0.3725345 0.6184463 1.88749e-4 0.6184463 0.3725346 0.5915654 0.3725346 0.6453271 1.88749e-4 0.645327 0.3725346 0.6184463 0.3725346 0.3387184 0.7442892 0.3528449 0.7231472 0.3708247 0.7051678 0.3708247 0.7051678 0.3919667 0.6910412 0.4154583 0.6813106 0.4154583 0.6813106 0.440397 0.6763502 0.3708247 0.7051678 0.440397 0.6763502 0.4658241 0.6763501 0.3708247 0.7051678 0.4658241 0.6763501 0.4907628 0.6813108 0.5142545 0.6910412 0.5142545 0.6910412 0.5353958 0.7051676 0.4658241 0.6763501 0.5353958 0.7051676 0.3708238 0.9056983 0.4658241 0.6763501 0.3708238 0.9056983 0.3528447 0.887719 0.3240271 0.8181468 0.3528447 0.887719 0.3387181 0.8665771 0.3240271 0.8181468 0.3387181 0.8665771 0.3289875 0.8430854 0.3240271 0.8181468 0.3240271 0.8181468 0.3240271 0.7927196 0.3708247 0.7051678 0.3240271 0.7927196 0.3289877 0.7677809 0.3708247 0.7051678 0.3289877 0.7677809 0.3387184 0.7442892 0.3708247 0.7051678 0.3708247 0.7051678 0.4658241 0.6763501 0.3708238 0.9056983 0.4597869 0.4413655 0.4885111 0.4413655 0.4885111 0.5454056 0.4885111 0.5454056 0.4885111 0.4413655 0.517236 0.4413655 0.517236 0.5454056 0.517236 0.4413655 0.5459611 0.4413655 0.4597869 0.4413655 0.4597869 0.4330044 0.4885111 0.4330044 0.545961 0.5454056 0.5459611 0.4413655 0.5746859 0.4413655 0.4885111 0.4330044 0.517236 0.4330044 0.517236 0.4413655 0.4597869 0.3729119 0.4885111 0.3729119 0.4885111 0.4330044 0.5746859 0.4413655 0.603411 0.4374563 0.6034109 0.5454056 0.517236 0.4413655 0.517236 0.4330044 0.5459611 0.4330044 0.4885111 0.4330044 0.4885111 0.3729119 0.517236 0.3729119 0.603411 0.4374563 0.6321359 0.4374563 0.6321359 0.4446169 0.5459611 0.4413655 0.5459611 0.4330044 0.5746859 0.4330044 0.517236 0.4330044 0.517236 0.3729119 0.545961 0.3729119 0.6321359 0.4374563 0.660861 0.4374563 0.660861 0.4446169 0.5746859 0.4330044 0.603411 0.4330044 0.603411 0.4374563 0.5459611 0.4330044 0.545961 0.3729119 0.5746859 0.3729119 0.603411 0.4330044 0.6321359 0.4330045 0.6321359 0.4374563 0.5746859 0.3729119 0.603411 0.3729119 0.603411 0.4330044 0.6321359 0.4330045 0.660861 0.4330045 0.660861 0.4374563 0.603411 0.3729119 0.6321359 0.372912 0.6321359 0.4330045 0.660861 0.4374563 0.660861 0.4330045 0.689586 0.4330045 0.6321359 0.4330045 0.6321359 0.372912 0.660861 0.372912 0.660861 0.4374563 0.689586 0.4374563 0.689586 0.4446169 0.689586 0.4374563 0.689586 0.4330045 0.718311 0.4330045 0.660861 0.4330045 0.660861 0.372912 0.6895861 0.372912 0.7757611 0.5454056 0.7757611 0.4374563 0.8044861 0.4374563 0.718311 0.4374563 0.718311 0.4330045 0.7470361 0.4330045 0.689586 0.4330045 0.6895861 0.372912 0.7183111 0.372912 0.8044861 0.4374563 0.8332111 0.4374563 0.8332111 0.5454057 0.7470361 0.4374563 0.7470361 0.4330045 0.7757611 0.4330045 0.718311 0.4330045 0.7183111 0.372912 0.7470361 0.372912 0.8332111 0.4374563 0.861936 0.4374563 0.861936 0.5454057 0.7757611 0.4374563 0.7757611 0.4330045 0.8044861 0.4330045 0.7470361 0.372912 0.7757611 0.372912 0.7757611 0.4330045 0.861936 0.4374563 0.890661 0.4374563 0.890661 0.5454057 0.8044861 0.4330045 0.8332111 0.4330045 0.8332111 0.4374563 0.7757611 0.372912 0.8044862 0.372912 0.8044861 0.4330045 0.890661 0.4374563 0.9193851 0.4374563 0.9193851 0.5454056 0.8332111 0.4330045 0.861936 0.4330045 0.861936 0.4374563 0.8044862 0.372912 0.8332111 0.372912 0.8332111 0.4330045 0.861936 0.4330045 0.890661 0.4330045 0.890661 0.4374563 0.8332111 0.372912 0.861936 0.372912 0.861936 0.4330045 0.890661 0.4374563 0.890661 0.4330045 0.9193851 0.4330045 0.861936 0.372912 0.890661 0.372912 0.890661 0.4330045 0.890661 0.372912 0.9193851 0.372912 0.9193851 0.4330045 0.890661 0.6026103 0.890661 0.5454057 0.9193851 0.5454056 0.8619362 0.6026103 0.861936 0.5454057 0.890661 0.5454057 0.8332111 0.5454057 0.861936 0.5454057 0.8619362 0.6026103 0.8044861 0.5454057 0.8332111 0.5454057 0.8332112 0.6026103 0.718311 0.4374563 0.718311 0.4446169 0.689586 0.4446169 0.7813857 0.6022767 0.7821273 0.6016363 0.7765093 0.5430507 0.7470361 0.4374563 0.7470361 0.4446169 0.718311 0.4446169 0.6034109 0.5454056 0.603411 0.4374563 0.6025581 0.4446181 0.7757611 0.4374563 0.7766139 0.4446181 0.7470361 0.4446169 0.5459609 0.6026102 0.545961 0.5454056 0.5746859 0.5454056 0.517236 0.6026102 0.517236 0.5454056 0.545961 0.5454056 0.488511 0.6026102 0.4885111 0.5454056 0.517236 0.5454056 0.4597868 0.6026102 0.4597868 0.5454056 0.4885111 0.5454056 0.5977775 0.6023113 0.5746859 0.6026102 0.5746859 0.5454056 0.6026628 0.5430507 0.6025581 0.4446181 0.6321359 0.4446169 0.6321359 0.4446169 0.660861 0.4446169 0.660861 0.5431588 0.660861 0.5431588 0.660861 0.4446169 0.689586 0.4446169 0.689586 0.5431588 0.689586 0.4446169 0.718311 0.4446169 0.7183111 0.5431588 0.718311 0.4446169 0.7470361 0.4446169 0.7470361 0.4446169 0.7766139 0.4446181 0.7765093 0.5430507 0.7757613 0.6759727 0.7708455 0.6014099 0.7821273 0.6016363 0.7470361 0.5431588 0.7765093 0.5430507 0.7708455 0.6014099 0.7183111 0.5431588 0.7470361 0.5431588 0.7433856 0.6014651 0.689586 0.5431588 0.7183111 0.5431588 0.7164566 0.6014651 0.6627154 0.6014651 0.660861 0.5431588 0.689586 0.5431588 0.6357864 0.6014651 0.6321358 0.5431588 0.660861 0.5431588 0.6083264 0.6014101 0.6026628 0.5430507 0.6321358 0.5431588 0.5970505 0.6016129 0.6083264 0.6014101 0.6034107 0.6759727 0.7757611 0.5454056 0.7765093 0.5430507 0.7766139 0.4446181 0.7557854 0.6999662 0.7705189 0.7146998 0.6061853 0.8495649 0.6061853 0.8495649 0.5946092 0.8322399 0.5866352 0.8129886 0.5866352 0.8129886 0.5825699 0.7925515 0.6061853 0.8495649 0.5825699 0.7925515 0.5825699 0.7717142 0.6061853 0.8495649 0.5825699 0.7717142 0.5866351 0.751277 0.5946093 0.7320258 0.5946093 0.7320258 0.6061859 0.7147002 0.6209203 0.6999658 0.6209203 0.6999658 0.6382458 0.6883893 0.6574972 0.6804152 0.6574972 0.6804152 0.6779342 0.6763501 0.6987715 0.6763501 0.6987715 0.6763501 0.7192084 0.6804153 0.7384598 0.6883894 0.7384598 0.6883894 0.7557854 0.6999662 0.6987715 0.6763501 0.7557854 0.6999662 0.6061853 0.8495649 0.6987715 0.6763501 0.5825699 0.7717142 0.5946093 0.7320258 0.6061853 0.8495649 0.5946093 0.7320258 0.6209203 0.6999658 0.6061853 0.8495649 0.6209203 0.6999658 0.6574972 0.6804152 0.6061853 0.8495649 0.2385286 0.6947575 0.2650171 0.7124563 0.05882138 0.9637051 0.05882138 0.9637051 0.03629481 0.9411785 1.8886e-4 0.8540101 0.03629481 0.9411785 0.01859521 0.9146893 1.8886e-4 0.8540101 0.01859521 0.9146893 0.006403744 0.8852562 1.8886e-4 0.8540101 1.8886e-4 0.8540101 1.88693e-4 0.8221517 0.006404101 0.7909057 0.006404101 0.7909057 0.01859563 0.7614725 0.03629517 0.7349835 0.03629517 0.7349835 0.05882251 0.7124562 0.08531177 0.6947571 0.08531177 0.6947571 0.1147449 0.6825653 0.145991 0.6763501 0.145991 0.6763501 0.1778494 0.6763504 0.2090953 0.6825655 0.2090953 0.6825655 0.2385286 0.6947575 0.145991 0.6763501 0.2385286 0.6947575 0.05882138 0.9637051 0.145991 0.6763501 1.8886e-4 0.8540101 0.006404101 0.7909057 0.03629517 0.7349835 0.03629517 0.7349835 0.08531177 0.6947571 0.05882138 0.9637051 0.08531177 0.6947571 0.145991 0.6763501 0.05882138 0.9637051 0.4597868 0.6026102 0.488511 0.6026102 0.4885107 0.6759727 0.4885107 0.6759727 0.488511 0.6026102 0.517236 0.6026102 0.517236 0.6026102 0.5459609 0.6026102 0.5459607 0.6759727 0.5459609 0.6026102 0.5746859 0.6026102 0.5746858 0.6759727 0.8044862 0.6026103 0.8332112 0.6026103 0.8332114 0.6759727 0.8332112 0.6026103 0.8619362 0.6026103 0.8619363 0.6759727 0.8619363 0.6759727 0.8619362 0.6026103 0.890661 0.6026103 0.8906613 0.6759727 0.890661 0.6026103 0.9193851 0.6026103 0.6083264 0.6014101 0.6357864 0.6014651 0.6321358 0.6759727 0.6357864 0.6014651 0.6627154 0.6014651 0.660861 0.6759727 0.6627154 0.6014651 0.6895861 0.6014651 0.6895861 0.6759727 0.6895861 0.6759727 0.6895861 0.6014651 0.7164566 0.6014651 0.7183111 0.6759727 0.7164566 0.6014651 0.7433856 0.6014651 0.7470363 0.6759727 0.7433856 0.6014651 0.7708455 0.6014099 0.7813857 0.6022767 0.7757611 0.5454056 0.8044861 0.5454057 0.5977775 0.6023113 0.6034109 0.5454056 0.6026628 0.5430507 0.2152348 0.3725345 0.1883539 0.3725345 0.1883539 1.88693e-4 0.1883539 1.88693e-4 0.1883539 0.3725345 0.161473 0.3725345 0.161473 1.88693e-4 0.161473 0.3725345 0.1345919 0.3725345 0.1345919 0.3725345 0.1077111 0.3725345 0.1077111 1.88693e-4 0.1077111 1.88693e-4 0.1077111 0.3725345 0.08083033 0.3725345 0.08083033 0.3725345 0.05394941 0.3725345 0.05394941 1.88693e-4 0.05394941 0.3725345 0.02706861 0.3725345 0.02706861 1.88693e-4 0.02706861 0.3725345 1.88693e-4 0.3725345 1.88693e-4 1.88693e-4 0.4302809 0.3725345 0.403401 0.3725345 0.4034009 1.88693e-4 0.4034009 1.88693e-4 0.403401 0.3725345 0.3765201 0.3725345 0.3765201 0.3725345 0.3496392 0.3725345 0.3496392 1.88693e-4 0.3496392 1.88693e-4 0.3496392 0.3725345 0.3227583 0.3725345 0.3227583 0.3725345 0.2958775 0.3725345 0.2958775 1.88693e-4 0.2958775 0.3725345 0.2689965 0.3725345 0.2689966 1.88693e-4 0.2689965 0.3725345 0.2421156 0.3725345 0.2421156 1.88693e-4 0.2421156 0.3725345 0.2152348 0.3725345 0.2152348 1.88693e-4 0.567501 0.8665767 0.5533747 0.8877184 0.5353949 0.9056982 0.5353949 0.9056982 0.5142529 0.9198247 0.4907611 0.9295551 0.4907611 0.9295551 0.4658224 0.9345158 0.4403952 0.9345157 0.4403952 0.9345157 0.4154567 0.929555 0.5353958 0.7051676 0.4154567 0.929555 0.391965 0.9198243 0.5353958 0.7051676 0.391965 0.9198243 0.3708238 0.9056983 0.5353958 0.7051676 0.5353958 0.7051676 0.5533751 0.7231468 0.5675014 0.7442888 0.5675014 0.7442888 0.5772321 0.7677806 0.5353958 0.7051676 0.5772321 0.7677806 0.5821925 0.7927193 0.5353958 0.7051676 0.5821925 0.7927193 0.5821925 0.8181464 0.5772319 0.8430849 0.5772319 0.8430849 0.567501 0.8665767 0.5821925 0.7927193 0.567501 0.8665767 0.5353949 0.9056982 0.5821925 0.7927193 0.5353949 0.9056982 0.4907611 0.9295551 0.5353958 0.7051676 0.4907611 0.9295551 0.4403952 0.9345157 0.5353958 0.7051676 0.4310627 0.5454056 0.4310626 0.4413655 0.4597869 0.4413655 0.4310627 0.5454056 0.4023378 0.5454056 0.4023378 0.4413655 0.4023378 0.5454056 0.3736127 0.5454056 0.3736127 0.4413655 0.4597869 0.4413655 0.4310626 0.4413655 0.4310626 0.4330044 0.3736127 0.5454056 0.3448879 0.5454056 0.3448879 0.4413655 0.4023378 0.4413655 0.4023378 0.4330044 0.4310626 0.4330044 0.4310626 0.4330044 0.4310626 0.3729119 0.4597869 0.3729119 0.3161628 0.5454056 0.3161628 0.4374563 0.3448879 0.4413655 0.4023378 0.4413655 0.3736127 0.4413655 0.3736127 0.4330044 0.4310626 0.4330044 0.4023378 0.4330044 0.4023378 0.3729119 0.3161628 0.4374563 0.3170157 0.4446181 0.2874379 0.4446169 0.3736127 0.4413655 0.3448879 0.4413655 0.3448879 0.4330044 0.4023378 0.4330044 0.3736127 0.4330044 0.3736128 0.3729119 0.2874379 0.4374563 0.2874379 0.4446169 0.2587127 0.4446169 0.3161628 0.4374563 0.3161628 0.4330044 0.3448879 0.4330044 0.3736127 0.4330044 0.3448879 0.4330044 0.3448879 0.3729119 0.2874379 0.4374563 0.2874379 0.4330044 0.3161628 0.4330044 0.3161628 0.4330044 0.3161628 0.3729119 0.3448879 0.3729119 0.2587128 0.4374563 0.2587128 0.4330044 0.2874379 0.4330044 0.2874379 0.4330044 0.2874379 0.3729119 0.3161628 0.3729119 0.2587128 0.4374563 0.2299878 0.4374563 0.2299878 0.4330044 0.2874379 0.4330044 0.2587128 0.4330044 0.2587128 0.3729119 0.2587128 0.4374563 0.2587127 0.4446169 0.2299878 0.4446169 0.2299878 0.4374563 0.2012628 0.4374563 0.2012628 0.4330044 0.2587128 0.4330044 0.2299878 0.4330044 0.2299878 0.3729119 0.1438127 0.5454056 0.1150878 0.5454056 0.1150878 0.4374563 0.2012628 0.4374563 0.1725376 0.4374563 0.1725376 0.4330044 0.2299878 0.4330044 0.2012628 0.4330044 0.2012627 0.3729119 0.08636265 0.5454056 0.08636265 0.4374563 0.1150878 0.4374563 0.1725376 0.4374563 0.1438126 0.4374563 0.1438126 0.4330044 0.2012628 0.4330044 0.1725376 0.4330044 0.1725378 0.3729119 0.05763763 0.5454056 0.05763775 0.4374563 0.08636265 0.4374563 0.1438126 0.4374563 0.1150878 0.4374563 0.1150878 0.4330044 0.1438126 0.4330044 0.1438127 0.3729119 0.1725378 0.3729119 0.02891278 0.5454056 0.02891278 0.4374563 0.05763775 0.4374563 0.08636265 0.4374563 0.08636265 0.4330044 0.1150878 0.4330044 0.1150878 0.4330044 0.1150876 0.3729119 0.1438127 0.3729119 1.88749e-4 0.5454055 1.88749e-4 0.4374563 0.02891278 0.4374563 0.05763775 0.4374563 0.05763775 0.4330044 0.08636265 0.4330044 0.08636265 0.4330044 0.08636265 0.3729119 0.1150876 0.3729119 0.02891278 0.4374563 0.02891278 0.4330044 0.05763775 0.4330044 0.05763775 0.4330044 0.05763775 0.3729119 0.08636265 0.3729119 0.02891278 0.4374563 1.88749e-4 0.4374563 1.88749e-4 0.4330044 0.02891278 0.4330044 0.0289129 0.3729119 0.05763775 0.3729119 1.88749e-4 0.4330044 1.88749e-4 0.3729119 0.0289129 0.3729119 0.02891266 0.6026102 1.88749e-4 0.6026102 1.88749e-4 0.5454055 0.05763763 0.6026102 0.02891266 0.6026102 0.02891278 0.5454056 0.05763763 0.6026102 0.05763763 0.5454056 0.08636265 0.5454056 0.08636254 0.6026102 0.08636265 0.5454056 0.1150878 0.5454056 0.2299878 0.4446169 0.2012628 0.4446169 0.2012628 0.4374563 0.1430646 0.5430507 0.1374465 0.6016363 0.1381881 0.6022766 0.2012628 0.4446169 0.1725376 0.4446169 0.1725376 0.4374563 0.3161628 0.5454056 0.3169111 0.5430507 0.3170157 0.4446181 0.1725376 0.4446169 0.1429599 0.4446181 0.1438126 0.4374563 0.3736128 0.6026102 0.3448879 0.6026102 0.3448879 0.5454056 0.4023379 0.6026102 0.3736128 0.6026102 0.3736127 0.5454056 0.4310628 0.6026102 0.4023379 0.6026102 0.4023378 0.5454056 0.4597868 0.6026102 0.4310628 0.6026102 0.4310627 0.5454056 0.3448879 0.5454056 0.3448879 0.6026102 0.3217962 0.6023113 0.3169111 0.5430507 0.2874379 0.5431588 0.2874379 0.4446169 0.2587128 0.5431588 0.2587127 0.4446169 0.2874379 0.4446169 0.2587128 0.5431588 0.2299878 0.5431588 0.2299878 0.4446169 0.2299878 0.5431588 0.2012627 0.5431588 0.2012628 0.4446169 0.2012627 0.5431588 0.1725376 0.5431588 0.1725376 0.4446169 0.1430646 0.5430507 0.1429599 0.4446181 0.1725376 0.4446169 0.1438124 0.6759727 0.1150874 0.6759727 0.1374465 0.6016363 0.1487283 0.6014099 0.1430646 0.5430507 0.1725376 0.5431588 0.1761882 0.6014651 0.1725376 0.5431588 0.2012627 0.5431588 0.2031171 0.6014651 0.2012627 0.5431588 0.2299878 0.5431588 0.2568583 0.6014651 0.2299878 0.6014651 0.2299878 0.5431588 0.2837874 0.6014651 0.2568583 0.6014651 0.2587128 0.5431588 0.3112474 0.60141 0.2837874 0.6014651 0.2874379 0.5431588 0.316163 0.6759727 0.3112474 0.60141 0.3225233 0.6016129 0.1429599 0.4446181 0.1430646 0.5430507 0.1438127 0.5454056 0.6061853 0.8495649 0.7705189 0.7146998 0.7820953 0.7320248 0.7820953 0.7320248 0.7900694 0.751276 0.7941345 0.771713 0.7941345 0.771713 0.7941344 0.7925503 0.7820953 0.7320248 0.7941344 0.7925503 0.7900693 0.8129873 0.7820953 0.7320248 0.7900693 0.8129873 0.7820953 0.8322385 0.7384586 0.8758753 0.7820953 0.8322385 0.7705186 0.8495643 0.7384586 0.8758753 0.7705186 0.8495643 0.7557843 0.8642986 0.7384586 0.8758753 0.7384586 0.8758753 0.7192074 0.8838492 0.6574959 0.8838493 0.7192074 0.8838492 0.6987704 0.8879144 0.6574959 0.8838493 0.6987704 0.8879144 0.6779329 0.8879144 0.6574959 0.8838493 0.6574959 0.8838493 0.6382448 0.8758751 0.620919 0.8642985 0.620919 0.8642985 0.6061853 0.8495649 0.6574959 0.8838493 0.6061853 0.8495649 0.7820953 0.7320248 0.6574959 0.8838493 0.7820953 0.7320248 0.7900693 0.8129873 0.6574959 0.8838493 0.05882138 0.9637051 0.2650171 0.7124563 0.2875431 0.7349833 0.2875431 0.7349833 0.305243 0.7614724 0.3174346 0.7909056 0.3174346 0.7909056 0.3236497 0.8221517 0.2875431 0.7349833 0.3236497 0.8221517 0.3236497 0.8540099 0.2875431 0.7349833 0.3236497 0.8540099 0.3174341 0.8852559 0.2650157 0.9637054 0.3174341 0.8852559 0.3052426 0.9146891 0.2650157 0.9637054 0.3052426 0.9146891 0.287543 0.9411783 0.2650157 0.9637054 0.2650157 0.9637054 0.2385264 0.9814047 0.2090932 0.9935964 0.2090932 0.9935964 0.1778471 0.9998114 0.2650157 0.9637054 0.1778471 0.9998114 0.1459888 0.9998114 0.2650157 0.9637054 0.1459888 0.9998114 0.1147428 0.9935961 0.08530962 0.9814042 0.08530962 0.9814042 0.05882138 0.9637051 0.1459888 0.9998114 0.05882138 0.9637051 0.2875431 0.7349833 0.1459888 0.9998114 0.2875431 0.7349833 0.3236497 0.8540099 0.2650157 0.9637054 0.431063 0.6759727 0.4310628 0.6026102 0.4597868 0.6026102 0.431063 0.6759727 0.402338 0.6759727 0.4023379 0.6026102 0.3736129 0.6759727 0.3736128 0.6026102 0.4023379 0.6026102 0.3448881 0.6759727 0.3448879 0.6026102 0.3736128 0.6026102 0.0863623 0.6759727 0.08636254 0.6026102 0.1150875 0.6026102 0.05763733 0.6759727 0.05763763 0.6026102 0.08636254 0.6026102 0.05763733 0.6759727 0.02891236 0.6759727 0.02891266 0.6026102 0.02891236 0.6759727 1.88693e-4 0.6759727 1.88749e-4 0.6026102 0.287438 0.6759727 0.2837874 0.6014651 0.3112474 0.60141 0.2587128 0.6759727 0.2568583 0.6014651 0.2837874 0.6014651 0.2299877 0.6759727 0.2299878 0.6014651 0.2568583 0.6014651 0.2299877 0.6759727 0.2012627 0.6759727 0.2031171 0.6014651 0.2012627 0.6759727 0.1725375 0.6759727 0.1761882 0.6014651 0.1725375 0.6759727 0.1438124 0.6759727 0.1487283 0.6014099 0.1150878 0.5454056 0.1438127 0.5454056 0.1381881 0.6022766 0.3169111 0.5430507 0.3161628 0.5454056 0.3217962 0.6023113 + + + + + + + + + + + + + + +

2 0 0 1 1 1 0 2 2 2 0 3 5 3 4 3 4 5 4 5 6 7 6 7 5 3 8 8 7 9 7 6 10 6 8 11 8 7 12 11 9 13 9 10 14 12 11 15 11 9 16 10 12 17 14 13 18 13 14 19 12 11 20 149 15 21 15 16 22 14 13 23 16 17 24 152 18 25 151 19 26 16 17 27 19 20 28 17 21 29 20 22 30 19 20 31 18 23 32 20 22 33 23 24 34 21 25 35 24 26 36 23 24 37 22 27 38 26 28 39 25 29 40 24 26 41 28 30 42 27 31 43 26 28 44 0 2 45 29 32 46 28 30 47 28 30 48 149 15 49 8 7 50 218 33 51 90 34 52 235 35 53 90 34 54 76 36 55 91 37 56 91 37 57 77 38 58 92 39 59 218 33 60 60 40 61 75 41 62 92 39 63 78 42 64 93 43 65 60 40 66 76 36 67 75 41 68 168 19 69 60 40 70 201 44 71 78 42 72 94 45 73 93 43 74 76 36 75 62 46 76 77 38 77 60 40 78 33 23 79 61 47 80 79 48 81 112 49 82 113 50 83 77 38 84 63 51 85 78 42 86 61 47 87 35 22 88 62 46 89 80 52 90 111 53 91 112 49 92 63 51 93 79 48 94 78 42 95 62 46 96 37 54 97 63 51 98 64 55 99 80 52 100 79 48 101 37 54 102 64 55 103 63 51 104 65 56 105 81 57 106 80 52 107 39 26 108 65 56 109 64 55 110 81 57 111 67 58 112 82 59 113 65 56 114 43 30 115 66 60 116 81 57 117 110 61 118 111 53 119 82 59 120 68 62 121 83 63 122 66 60 123 45 2 124 67 58 125 95 64 126 86 65 127 96 66 128 83 63 129 69 67 130 84 68 131 67 58 132 47 0 133 68 62 134 86 65 135 97 69 136 96 66 137 84 68 138 70 70 139 85 71 140 68 62 141 49 5 142 69 67 143 87 72 144 98 73 145 97 69 146 85 71 147 71 74 148 86 65 149 49 5 150 70 70 151 69 67 152 88 75 153 99 76 154 98 73 155 71 74 156 87 72 157 86 65 158 51 8 159 71 74 160 70 70 161 89 77 162 246 78 163 99 76 164 72 79 165 88 75 166 87 72 167 53 80 168 72 79 169 71 74 170 73 81 171 89 77 172 88 75 173 55 12 174 73 81 175 72 79 176 89 77 177 217 82 178 234 83 179 57 11 180 74 84 181 73 81 182 59 13 183 217 82 184 74 84 185 121 85 186 246 78 187 270 86 188 120 87 189 99 76 190 121 85 191 97 69 192 120 87 193 119 88 194 96 66 195 119 88 196 118 89 197 83 63 198 110 61 199 82 59 200 130 90 201 106 91 202 95 64 203 84 68 204 109 92 205 83 63 206 36 93 207 131 94 208 132 95 209 94 45 210 113 50 211 100 96 212 85 71 213 107 97 214 84 68 215 116 98 216 93 43 217 117 99 218 115 100 219 92 39 220 116 98 221 114 101 222 91 37 223 115 100 224 261 102 225 90 34 226 114 101 227 131 94 228 93 43 229 94 45 230 52 103 231 130 90 232 118 89 233 100 96 234 112 49 235 101 104 236 112 49 237 102 105 238 101 104 239 102 105 240 110 61 241 103 106 242 103 106 243 109 92 244 104 107 245 104 107 246 107 97 247 105 108 248 107 97 249 106 91 250 105 108 251 50 109 252 129 110 253 52 103 254 105 108 255 127 111 256 126 112 257 104 107 258 126 112 259 125 113 260 103 106 261 125 113 262 124 114 263 123 115 264 103 106 265 124 114 266 122 116 267 102 105 268 123 115 269 128 117 270 101 104 271 122 116 272 132 95 273 38 118 274 36 93 275 95 64 276 108 119 277 85 71 278 48 120 279 52 103 280 167 121 281 200 15 282 53 80 283 45 2 284 261 102 285 30 122 286 167 121 287 30 122 288 115 100 289 32 123 290 115 100 291 34 124 292 32 123 293 116 98 294 36 93 295 34 124 296 118 89 297 54 125 298 52 103 299 119 88 300 56 126 301 54 125 302 56 126 303 121 85 304 58 127 305 58 127 306 270 86 307 199 128 308 128 117 309 40 129 310 38 118 311 122 116 312 42 130 313 40 129 314 123 115 315 44 131 316 42 130 317 44 131 318 125 113 319 46 132 320 46 132 321 126 112 322 48 120 323 48 120 324 127 111 325 50 109 326 130 90 327 96 66 328 118 89 329 129 110 330 127 111 331 106 91 332 129 110 333 130 90 334 52 103 335 131 94 336 100 96 337 132 95 338 117 99 339 131 94 340 36 93 341 128 117 342 132 95 343 100 96 344 134 133 345 135 134 346 133 135 347 135 134 348 138 136 349 137 137 350 137 137 351 140 138 352 139 139 353 140 138 354 141 140 355 139 139 356 141 140 357 144 141 358 143 142 359 144 141 360 145 143 361 143 142 362 146 144 363 147 145 364 145 143 365 148 146 366 149 15 367 147 145 368 152 18 369 153 147 370 151 19 371 153 147 372 156 148 373 155 149 374 156 148 375 157 150 376 155 149 377 157 150 378 160 151 379 159 152 380 160 151 381 161 153 382 159 152 383 162 154 384 163 155 385 161 153 386 164 156 387 165 157 388 163 155 389 166 158 390 133 135 391 165 157 392 135 134 393 151 19 394 159 152 395 236 159 396 218 33 397 235 35 398 236 159 399 220 160 400 219 161 401 237 162 402 221 163 403 220 160 404 218 33 405 202 164 406 201 44 407 238 165 408 222 166 409 221 163 410 220 160 411 202 164 412 219 161 413 202 164 414 168 19 415 201 44 416 240 167 417 222 166 418 239 168 419 220 160 420 204 169 421 203 170 422 202 164 423 172 149 424 170 147 425 223 171 426 259 172 427 224 173 428 221 163 429 205 174 430 204 169 431 203 170 432 174 150 433 172 149 434 224 173 435 258 175 436 225 176 437 223 171 438 205 174 439 222 166 440 204 169 441 176 152 442 174 150 443 224 173 444 206 177 445 223 171 446 206 177 447 176 152 448 205 174 449 225 176 450 207 178 451 224 173 452 207 178 453 178 153 454 206 177 455 225 176 456 209 179 457 208 180 458 207 178 459 182 157 460 180 155 461 225 176 462 257 181 463 226 182 464 226 182 465 210 183 466 209 179 467 208 180 468 184 135 469 182 157 470 241 184 471 230 185 472 229 186 473 227 187 474 211 188 475 210 183 476 209 179 477 186 134 478 184 135 479 243 189 480 230 185 481 242 190 482 228 191 483 212 192 484 211 188 485 210 183 486 188 193 487 186 134 488 244 194 489 231 195 490 243 189 491 229 186 492 213 196 493 212 192 494 212 192 495 188 193 496 211 188 497 245 197 498 232 198 499 244 194 500 231 195 501 213 196 502 230 185 503 213 196 504 190 139 505 212 192 506 246 78 507 233 199 508 245 197 509 232 198 510 214 200 511 231 195 512 214 200 513 192 201 514 213 196 515 233 199 516 215 202 517 232 198 518 215 202 519 194 142 520 214 200 521 233 199 522 217 82 523 216 203 524 216 203 525 196 143 526 215 202 527 217 82 528 198 204 529 216 203 530 269 205 531 246 78 532 245 197 533 268 206 534 245 197 535 244 194 536 268 206 537 243 189 538 267 207 539 267 207 540 242 190 541 266 208 542 257 181 543 227 187 544 226 182 545 253 209 546 279 210 547 241 184 548 256 211 549 228 191 550 227 187 551 175 212 552 281 213 553 280 214 554 240 167 555 260 215 556 223 171 557 254 216 558 229 186 559 228 191 560 264 217 561 239 168 562 238 165 563 263 218 564 238 165 565 237 162 566 262 219 567 237 162 568 236 159 569 261 102 570 236 159 571 235 35 572 239 168 573 280 214 574 240 167 575 191 220 576 266 208 577 279 210 578 247 221 579 259 172 580 260 215 581 249 222 582 259 172 583 248 223 584 249 222 585 257 181 586 258 175 587 250 224 588 256 211 589 257 181 590 251 225 591 254 216 592 256 211 593 253 209 594 254 216 595 252 226 596 189 227 597 278 228 598 276 229 599 276 229 600 252 226 601 275 230 602 275 230 603 251 225 604 274 231 605 274 231 606 250 224 607 273 232 608 272 233 609 250 224 610 249 222 611 271 234 612 249 222 613 248 223 614 277 235 615 248 223 616 247 221 617 177 236 618 281 213 619 175 212 620 255 237 621 241 184 622 229 186 623 189 227 624 181 238 625 173 239 626 170 147 627 186 134 628 194 142 629 169 240 630 261 102 631 167 121 632 169 240 633 263 218 634 262 219 635 173 239 636 263 218 637 171 241 638 175 212 639 264 217 640 173 239 641 193 242 642 266 208 643 191 220 644 195 243 645 267 207 646 193 242 647 195 243 648 269 205 649 268 206 650 197 244 651 270 86 652 269 205 653 179 245 654 277 235 655 177 236 656 181 238 657 271 234 658 179 245 659 183 246 660 272 233 661 181 238 662 183 246 663 274 231 664 273 232 665 185 247 666 275 230 667 274 231 668 187 248 669 276 229 670 275 230 671 242 190 672 279 210 673 266 208 674 278 228 675 253 209 676 276 229 677 278 228 678 191 220 679 279 210 680 247 221 681 280 214 682 281 213 683 265 249 684 175 212 685 280 214 686 277 235 687 247 221 688 281 213 689 2 0 690 3 4 691 1 1 692 2 0 693 4 5 694 5 3 695 4 5 696 6 8 697 7 6 698 8 7 699 9 10 700 7 6 701 8 7 702 10 12 703 11 9 704 12 11 705 13 14 706 11 9 707 14 13 708 15 16 709 13 14 710 149 15 711 150 250 712 15 16 713 16 17 714 17 21 715 152 18 716 16 17 717 18 23 718 19 20 719 20 22 720 21 25 721 19 20 722 20 22 723 22 27 724 23 24 725 24 26 726 25 29 727 23 24 728 26 28 729 27 31 730 25 29 731 28 30 732 29 32 733 27 31 734 0 2 735 1 1 736 29 32 737 2 0 738 0 2 739 28 30 740 28 30 741 26 28 742 24 26 743 24 26 744 22 27 745 28 30 746 22 27 747 20 22 748 28 30 749 20 22 750 18 23 751 16 17 752 16 17 753 151 19 754 20 22 755 151 19 756 149 15 757 20 22 758 149 15 759 14 13 760 8 7 761 14 13 762 12 11 763 8 7 764 12 11 765 10 12 766 8 7 767 8 7 768 6 8 769 28 30 770 6 8 771 4 5 772 28 30 773 4 5 774 2 0 775 28 30 776 28 30 777 20 22 778 149 15 779 218 33 780 75 41 781 90 34 782 90 34 783 75 41 784 76 36 785 91 37 786 76 36 787 77 38 788 218 33 789 201 44 790 60 40 791 92 39 792 77 38 793 78 42 794 60 40 795 61 47 796 76 36 797 168 19 798 31 251 799 60 40 800 78 42 801 79 48 802 94 45 803 76 36 804 61 47 805 62 46 806 60 40 807 31 251 808 33 23 809 79 48 810 80 52 811 112 49 812 77 38 813 62 46 814 63 51 815 61 47 816 33 23 817 35 22 818 80 52 819 81 57 820 111 53 821 63 51 822 64 55 823 79 48 824 62 46 825 35 22 826 37 54 827 64 55 828 65 56 829 80 52 830 37 54 831 39 26 832 64 55 833 65 56 834 66 60 835 81 57 836 39 26 837 41 28 838 65 56 839 81 57 840 66 60 841 67 58 842 65 56 843 41 28 844 43 30 845 81 57 846 82 59 847 110 61 848 82 59 849 67 58 850 68 62 851 66 60 852 43 30 853 45 2 854 95 64 855 85 71 856 86 65 857 83 63 858 68 62 859 69 67 860 67 58 861 45 2 862 47 0 863 86 65 864 87 72 865 97 69 866 84 68 867 69 67 868 70 70 869 68 62 870 47 0 871 49 5 872 87 72 873 88 75 874 98 73 875 85 71 876 70 70 877 71 74 878 49 5 879 51 8 880 70 70 881 88 75 882 89 77 883 99 76 884 71 74 885 72 79 886 87 72 887 51 8 888 53 80 889 71 74 890 89 77 891 234 83 892 246 78 893 72 79 894 73 81 895 88 75 896 53 80 897 55 12 898 72 79 899 73 81 900 74 84 901 89 77 902 55 12 903 57 11 904 73 81 905 89 77 906 74 84 907 217 82 908 57 11 909 59 13 910 74 84 911 59 13 912 200 15 913 217 82 914 121 85 915 99 76 916 246 78 917 120 87 918 98 73 919 99 76 920 97 69 921 98 73 922 120 87 923 96 66 924 97 69 925 119 88 926 83 63 927 109 92 928 110 61 929 130 90 930 129 110 931 106 91 932 84 68 933 107 97 934 109 92 935 94 45 936 79 48 937 113 50 938 85 71 939 108 119 940 107 97 941 116 98 942 92 39 943 93 43 944 115 100 945 91 37 946 92 39 947 114 101 948 90 34 949 91 37 950 261 102 951 235 35 952 90 34 953 131 94 954 117 99 955 93 43 956 100 96 957 113 50 958 112 49 959 112 49 960 111 53 961 102 105 962 102 105 963 111 53 964 110 61 965 103 106 966 110 61 967 109 92 968 104 107 969 109 92 970 107 97 971 107 97 972 108 119 973 106 91 974 50 109 975 127 111 976 129 110 977 105 108 978 106 91 979 127 111 980 104 107 981 105 108 982 126 112 983 103 106 984 104 107 985 125 113 986 123 115 987 102 105 988 103 106 989 122 116 990 101 104 991 102 105 992 128 117 993 100 96 994 101 104 995 132 95 996 128 117 997 38 118 998 95 64 999 106 91 1000 108 119 1001 58 127 1002 199 128 1003 167 121 1004 167 121 1005 30 122 1006 32 123 1007 32 123 1008 34 124 1009 167 121 1010 34 124 1011 36 93 1012 167 121 1013 36 93 1014 38 118 1015 40 129 1016 40 129 1017 42 130 1018 44 131 1019 44 131 1020 46 132 1021 48 120 1022 48 120 1023 50 109 1024 52 103 1025 52 103 1026 54 125 1027 56 126 1028 56 126 1029 58 127 1030 52 103 1031 58 127 1032 167 121 1033 52 103 1034 36 93 1035 40 129 1036 167 121 1037 40 129 1038 44 131 1039 167 121 1040 44 131 1041 48 120 1042 167 121 1043 31 251 1044 168 19 1045 200 15 1046 200 15 1047 59 13 1048 53 80 1049 59 13 1050 57 11 1051 53 80 1052 57 11 1053 55 12 1054 53 80 1055 53 80 1056 51 8 1057 49 5 1058 49 5 1059 47 0 1060 45 2 1061 45 2 1062 43 30 1063 41 28 1064 41 28 1065 39 26 1066 37 54 1067 37 54 1068 35 22 1069 33 23 1070 33 23 1071 31 251 1072 37 54 1073 31 251 1074 200 15 1075 37 54 1076 53 80 1077 49 5 1078 45 2 1079 45 2 1080 41 28 1081 200 15 1082 41 28 1083 37 54 1084 200 15 1085 261 102 1086 114 101 1087 30 122 1088 30 122 1089 114 101 1090 115 100 1091 115 100 1092 116 98 1093 34 124 1094 116 98 1095 117 99 1096 36 93 1097 118 89 1098 119 88 1099 54 125 1100 119 88 1101 120 87 1102 56 126 1103 56 126 1104 120 87 1105 121 85 1106 58 127 1107 121 85 1108 270 86 1109 128 117 1110 122 116 1111 40 129 1112 122 116 1113 123 115 1114 42 130 1115 123 115 1116 124 114 1117 44 131 1118 44 131 1119 124 114 1120 125 113 1121 46 132 1122 125 113 1123 126 112 1124 48 120 1125 126 112 1126 127 111 1127 130 90 1128 95 64 1129 96 66 1130 131 94 1131 94 45 1132 100 96 1133 134 133 1134 136 252 1135 135 134 1136 135 134 1137 136 252 1138 138 136 1139 137 137 1140 138 136 1141 140 138 1142 140 138 1143 142 253 1144 141 140 1145 141 140 1146 142 253 1147 144 141 1148 144 141 1149 146 144 1150 145 143 1151 146 144 1152 148 146 1153 147 145 1154 148 146 1155 150 250 1156 149 15 1157 152 18 1158 154 254 1159 153 147 1160 153 147 1161 154 254 1162 156 148 1163 156 148 1164 158 255 1165 157 150 1166 157 150 1167 158 255 1168 160 151 1169 160 151 1170 162 154 1171 161 153 1172 162 154 1173 164 156 1174 163 155 1175 164 156 1176 166 158 1177 165 157 1178 166 158 1179 134 133 1180 133 135 1181 165 157 1182 133 135 1183 135 134 1184 135 134 1185 137 137 1186 139 139 1187 139 139 1188 141 140 1189 143 142 1190 143 142 1191 145 143 1192 151 19 1193 145 143 1194 147 145 1195 151 19 1196 147 145 1197 149 15 1198 151 19 1199 151 19 1200 153 147 1201 155 149 1202 155 149 1203 157 150 1204 151 19 1205 157 150 1206 159 152 1207 151 19 1208 159 152 1209 161 153 1210 163 155 1211 163 155 1212 165 157 1213 159 152 1214 165 157 1215 135 134 1216 159 152 1217 135 134 1218 139 139 1219 151 19 1220 139 139 1221 143 142 1222 151 19 1223 236 159 1224 219 161 1225 218 33 1226 236 159 1227 237 162 1228 220 160 1229 237 162 1230 238 165 1231 221 163 1232 218 33 1233 219 161 1234 202 164 1235 238 165 1236 239 168 1237 222 166 1238 220 160 1239 203 170 1240 202 164 1241 202 164 1242 170 147 1243 168 19 1244 240 167 1245 223 171 1246 222 166 1247 220 160 1248 221 163 1249 204 169 1250 202 164 1251 203 170 1252 172 149 1253 223 171 1254 260 215 1255 259 172 1256 221 163 1257 222 166 1258 205 174 1259 203 170 1260 204 169 1261 174 150 1262 224 173 1263 259 172 1264 258 175 1265 223 171 1266 206 177 1267 205 174 1268 204 169 1269 205 174 1270 176 152 1271 224 173 1272 207 178 1273 206 177 1274 206 177 1275 178 153 1276 176 152 1277 225 176 1278 208 180 1279 207 178 1280 207 178 1281 180 155 1282 178 153 1283 225 176 1284 226 182 1285 209 179 1286 207 178 1287 208 180 1288 182 157 1289 225 176 1290 258 175 1291 257 181 1292 226 182 1293 227 187 1294 210 183 1295 208 180 1296 209 179 1297 184 135 1298 241 184 1299 242 190 1300 230 185 1301 227 187 1302 228 191 1303 211 188 1304 209 179 1305 210 183 1306 186 134 1307 243 189 1308 231 195 1309 230 185 1310 228 191 1311 229 186 1312 212 192 1313 210 183 1314 211 188 1315 188 193 1316 244 194 1317 232 198 1318 231 195 1319 229 186 1320 230 185 1321 213 196 1322 212 192 1323 190 139 1324 188 193 1325 245 197 1326 233 199 1327 232 198 1328 231 195 1329 214 200 1330 213 196 1331 213 196 1332 192 201 1333 190 139 1334 246 78 1335 234 83 1336 233 199 1337 232 198 1338 215 202 1339 214 200 1340 214 200 1341 194 142 1342 192 201 1343 233 199 1344 216 203 1345 215 202 1346 215 202 1347 196 143 1348 194 142 1349 233 199 1350 234 83 1351 217 82 1352 216 203 1353 198 204 1354 196 143 1355 217 82 1356 200 15 1357 198 204 1358 269 205 1359 270 86 1360 246 78 1361 268 206 1362 269 205 1363 245 197 1364 268 206 1365 244 194 1366 243 189 1367 267 207 1368 243 189 1369 242 190 1370 257 181 1371 256 211 1372 227 187 1373 253 209 1374 278 228 1375 279 210 1376 256 211 1377 254 216 1378 228 191 1379 240 167 1380 247 221 1381 260 215 1382 254 216 1383 255 237 1384 229 186 1385 264 217 1386 265 249 1387 239 168 1388 263 218 1389 264 217 1390 238 165 1391 262 219 1392 263 218 1393 237 162 1394 261 102 1395 262 219 1396 236 159 1397 239 168 1398 265 249 1399 280 214 1400 247 221 1401 248 223 1402 259 172 1403 249 222 1404 258 175 1405 259 172 1406 249 222 1407 250 224 1408 257 181 1409 250 224 1410 251 225 1411 256 211 1412 251 225 1413 252 226 1414 254 216 1415 253 209 1416 255 237 1417 254 216 1418 189 227 1419 191 220 1420 278 228 1421 276 229 1422 253 209 1423 252 226 1424 275 230 1425 252 226 1426 251 225 1427 274 231 1428 251 225 1429 250 224 1430 272 233 1431 273 232 1432 250 224 1433 271 234 1434 272 233 1435 249 222 1436 277 235 1437 271 234 1438 248 223 1439 177 236 1440 277 235 1441 281 213 1442 255 237 1443 253 209 1444 241 184 1445 167 121 1446 199 128 1447 197 244 1448 197 244 1449 195 243 1450 193 242 1451 193 242 1452 191 220 1453 197 244 1454 191 220 1455 189 227 1456 197 244 1457 189 227 1458 187 248 1459 181 238 1460 187 248 1461 185 247 1462 181 238 1463 185 247 1464 183 246 1465 181 238 1466 181 238 1467 179 245 1468 173 239 1469 179 245 1470 177 236 1471 173 239 1472 177 236 1473 175 212 1474 173 239 1475 173 239 1476 171 241 1477 169 240 1478 169 240 1479 167 121 1480 173 239 1481 167 121 1482 197 244 1483 173 239 1484 197 244 1485 189 227 1486 173 239 1487 200 15 1488 168 19 1489 170 147 1490 170 147 1491 172 149 1492 174 150 1493 174 150 1494 176 152 1495 170 147 1496 176 152 1497 178 153 1498 170 147 1499 178 153 1500 180 155 1501 186 134 1502 180 155 1503 182 157 1504 186 134 1505 182 157 1506 184 135 1507 186 134 1508 186 134 1509 188 193 1510 190 139 1511 190 139 1512 192 201 1513 186 134 1514 192 201 1515 194 142 1516 186 134 1517 194 142 1518 196 143 1519 198 204 1520 198 204 1521 200 15 1522 194 142 1523 200 15 1524 170 147 1525 194 142 1526 170 147 1527 178 153 1528 186 134 1529 169 240 1530 262 219 1531 261 102 1532 169 240 1533 171 241 1534 263 218 1535 173 239 1536 264 217 1537 263 218 1538 175 212 1539 265 249 1540 264 217 1541 193 242 1542 267 207 1543 266 208 1544 195 243 1545 268 206 1546 267 207 1547 195 243 1548 197 244 1549 269 205 1550 197 244 1551 199 128 1552 270 86 1553 179 245 1554 271 234 1555 277 235 1556 181 238 1557 272 233 1558 271 234 1559 183 246 1560 273 232 1561 272 233 1562 183 246 1563 185 247 1564 274 231 1565 185 247 1566 187 248 1567 275 230 1568 187 248 1569 189 227 1570 276 229 1571 242 190 1572 241 184 1573 279 210 1574 247 221 1575 240 167 1576 280 214 1577

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/models/dave_sensor_models/meshes/blueview_p900/tx-p900.png b/models/dave_sensor_models/meshes/blueview_p900/tx-p900.png new file mode 100644 index 00000000..2aca5e77 Binary files /dev/null and b/models/dave_sensor_models/meshes/blueview_p900/tx-p900.png differ diff --git a/models/dave_worlds/worlds/dave_multibeam_sonar.world b/models/dave_worlds/worlds/dave_multibeam_sonar.world new file mode 100644 index 00000000..9046d264 --- /dev/null +++ b/models/dave_worlds/worlds/dave_multibeam_sonar.world @@ -0,0 +1,235 @@ + + + + + + 0.001 + 1.0 + + + + + ogre2 + + + + + + + + + + + + + 3D View + false + docked + + + ogre2 + scene + 0.4 0.4 0.4 + 0.8 0.8 0.8 + -6 0 6 0 0.5 0 + + + + + + floating + 5 + 5 + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + false + 5 + 5 + floating + false + + + + + + + World control + false + false + 72 + 1 + + floating + + + + + + + true + true + true + true + + + + + + World stats + false + false + 110 + 290 + 1 + + floating + + + + + + + true + true + true + true + + + + + + docked + + + + + + + docked + + + + + + + RGB camera + floating + 350 + 315 + + /sensor/camera + false + + + + Depth camera + floating + 350 + 315 + 500 + + /sensor/depth_camera + false + + + + + + Multibeam Sonar PointCloud + docked + + /sensor/multibeam_sonar/point_cloud + /sensor/multibeam_sonar/point_cloud_float_vector + + + + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Ground Plane + + 0 0 0 0 0 0 + + + + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun + + + + + 0 -1 0.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 0 1 3 0.0 0.0 1.57 + + https://fuel.gazebosim.org/1.0/OpenRobotics/models/Construction Cone + + + + + diff --git a/models/dave_worlds/worlds/dvl_world.world b/models/dave_worlds/worlds/dvl_world.world index bf36b12c..226eac13 100644 --- a/models/dave_worlds/worlds/dvl_world.world +++ b/models/dave_worlds/worlds/dvl_world.world @@ -42,6 +42,9 @@ filename="gz-sim-scene-broadcaster-system" name="gz::sim::systems::SceneBroadcaster"> +