commit 7a351cb41ebf6c0b5dc0ab76541412a733e0903d Author: NuoDaJia02 Date: Fri Oct 24 11:12:14 2025 +0800 add first version code diff --git a/arm_keyboard_input/CMakeLists.txt b/arm_keyboard_input/CMakeLists.txt new file mode 100644 index 0000000..8f19fe1 --- /dev/null +++ b/arm_keyboard_input/CMakeLists.txt @@ -0,0 +1,41 @@ +cmake_minimum_required(VERSION 3.8) +project(arm_keyboard_input) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() +add_compile_options(-g) + +include_directories( + include + ${CMAKE_CURRENT_SOURCE_DIR}/../include + ${EIGEN3_INCLUDE_DIRS} # 引入Eigen3的头文件路径 +) + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(interfaces REQUIRED) +find_package(gjk_interface REQUIRED) +find_package(rclcpp_action REQUIRED) + +# 设置源文件 +set(SOURCES + src/arm_keyboard_node.cpp +) + +add_executable(arm_keyboard_input ${SOURCES}) +ament_target_dependencies(arm_keyboard_input + rclcpp + std_msgs + rclcpp_action + gjk_interface + interfaces +) + +install(TARGETS + arm_keyboard_input + DESTINATION lib/${PROJECT_NAME}) + +ament_package() diff --git a/arm_keyboard_input/LICENSE b/arm_keyboard_input/LICENSE new file mode 100644 index 0000000..d645695 --- /dev/null +++ b/arm_keyboard_input/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. diff --git a/arm_keyboard_input/include/arm_keyboard_node.hpp b/arm_keyboard_input/include/arm_keyboard_node.hpp new file mode 100644 index 0000000..da0c4f1 --- /dev/null +++ b/arm_keyboard_input/include/arm_keyboard_node.hpp @@ -0,0 +1,53 @@ +#ifndef ARM_KEYBOARD_NODE_HPP +#define ARM_KEYBOARD_NODE_HPP + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/float64_multi_array.hpp" +#include "rclcpp_action/rclcpp_action.hpp" +#include "interfaces/action/arm.hpp" +#include "arm_define.h" +#include "rm_define.h" + +using ArmAction = interfaces::action::Arm; +using GoalClientArm = rclcpp_action::Client; +using GoalHandleArm = rclcpp_action::ClientGoalHandle; + +class ArmKeyboardNode: public rclcpp::Node +{ +public: + ArmKeyboardNode(); + ~ArmKeyboardNode(); + static rclcpp::Publisher::SharedPtr leftArmAimPub_; + static rclcpp::Publisher::SharedPtr rightArmAimPub_; + std::atomic exit_flag; + GoalClientArm::SharedPtr client_ptr_; + void SendAngleSteppingGoal(const char *command); + void SendAngleMovingGoal(const float *values, int armId); + void SendDirectSteppingGoal(const char *command); + void SendDirectMovingGoal(const float *values, int armId); + void SendDirectSteppingGoal2(const float *values, int armId); + void StopGoal(); +private: + std::shared_mutex rw_mutex_; + void goal_response_callback(GoalHandleArm::SharedPtr goal_handle); + void feedback_callback( + GoalHandleArm::SharedPtr goal_handle, + const std::shared_ptr feedback); + void result_callback(const GoalHandleArm::WrappedResult & result); + + rclcpp_action::Client::SendGoalOptions goal_options_; + + double leftArmAngleAim_[USED_ARM_DOF]; + double rightArmAngleAim_[USED_ARM_DOF]; + + int64_t leftCommandId_; + int64_t rightCommandId_; + + int leftDirectCommand_; + int rightDirectCommand_; + + GoalHandleArm::SharedPtr leftArmGoalHandle_; + GoalHandleArm::SharedPtr rightArmGoalHandle_; +}; + +#endif // ARM_KEYBOARD_NODE_HPP \ No newline at end of file diff --git a/arm_keyboard_input/package.xml b/arm_keyboard_input/package.xml new file mode 100644 index 0000000..5e82f35 --- /dev/null +++ b/arm_keyboard_input/package.xml @@ -0,0 +1,20 @@ + + + + arm_keyboard_input + 0.0.0 + arm_keyboard_input + zj + Apache-2.0 + + ament_cmake + interfaces + rclcpp + gjk_interface + rclcpp_action + std_msgs + + + ament_cmake + + diff --git a/arm_keyboard_input/src/arm_keyboard_node.cpp b/arm_keyboard_input/src/arm_keyboard_node.cpp new file mode 100644 index 0000000..241cb8d --- /dev/null +++ b/arm_keyboard_input/src/arm_keyboard_node.cpp @@ -0,0 +1,860 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_keyboard_node.hpp" +#include "gjk_interface.hpp" + +rclcpp::Publisher::SharedPtr ArmKeyboardNode::leftArmAimPub_; +rclcpp::Publisher::SharedPtr ArmKeyboardNode::rightArmAimPub_; + +std::thread inputThread_; +std::mutex armAimMutex_; +int64_t commandId = 0; +using namespace std::placeholders; +using namespace Eigen; + +const std::unordered_map keyToCommand = { + {KEY_A, 0}, {KEY_S, 1}, {KEY_D, 2}, {KEY_F, 3}, {KEY_G, 4}, {KEY_H, 5}, + {KEY_Z, 6}, {KEY_X, 7}, {KEY_C, 8}, {KEY_V, 9}, {KEY_B, 10}, {KEY_N, 11}, + {KEY_W, 12}, {KEY_E, 13}, {KEY_R, 14} +}; +enum { + KEEP_ACTION = 0, + STOP_ACTION = 1, + NEW_ACTION = 2 +}; + +void SetNonCanonicalMode(bool enable) { + static struct termios oldt, newt; + + if (enable) { + // 保存当前终端设置 + tcgetattr(STDIN_FILENO, &oldt); + newt = oldt; + + // 禁用缓冲和回显 + newt.c_lflag &= ~(ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &newt); + } else { + // 恢复终端设置 + oldt.c_lflag |= (ICANON | ECHO); + tcsetattr(STDIN_FILENO, TCSANOW, &oldt); + } +} + +std::string to_lower(const std::string& str) { + std::string res; + for (char c : str) { + res += tolower(c); + } + return res; +} + +// 检查设备名称是否包含键盘关键词 +bool is_keyboard_device(const std::string& event_path) { + // 设备名称文件路径:/sys/class/input/eventX/device/name + std::string name_path = "/sys/class/input/" + event_path + "/device/name"; + + // 读取设备名称 + std::ifstream name_file(name_path); + if (!name_file.is_open()) { + return false; + } + + std::string name; + std::getline(name_file, name); + name_file.close(); + + // 检查名称是否包含键盘相关关键词 + std::string lower_name = to_lower(name); + const std::vector keywords = {"keyboard"}; + for (const auto& kw : keywords) { + if (lower_name.find(kw) != std::string::npos) { + return true; + } + } + return false; +} + +// 查找所有输入设备并筛选出键盘 +std::string find_keyboard_devices() { + const std::string input_dir = "/sys/class/input/"; // 输入设备的sysfs目录 + + // 打开sysfs输入设备目录 + DIR* dir = opendir(input_dir.c_str()); + if (!dir) { + std::cerr << "无法打开目录: " << input_dir << std::endl; + return ""; + } + + // 遍历所有event设备(event0, event1, ...) + dirent* entry; + while ((entry = readdir(dir)) != nullptr) { + std::string entry_name = entry->d_name; + + // 只处理event开头的设备(输入设备通常以event命名) + if (entry_name.substr(0, 5) != "event") { + continue; + } + + // 检查该设备是否为键盘 + if (is_keyboard_device(entry_name)) { + // 转换为/dev/input/eventX格式的设备路径 + std::string device_path = "/dev/input/" + entry_name; + + // 打印设备信息(可选) + std::ifstream name_file("/sys/class/input/" + entry_name + "/device/name"); + std::string name; + std::getline(name_file, name); + std::cout << "找到键盘设备: " << device_path << " (" << name << ")" << std::endl; + return device_path; + } + } + + closedir(dir); + return ""; +} + +void KeyboardInputAngleStepping(std::shared_ptr armNode) { + // 设置终端为无缓冲模式 + std::cout << "q:退出,[a,s,d,f,g,h]:左臂控制,[z,x,c,v,b,n]:右臂控制" << std::endl; + SetNonCanonicalMode(true); + + std::string device = find_keyboard_devices(); + std::cout << "找到键盘设备: " << device << std::endl; + const char* device_path = device.c_str(); // 替换为你的键盘设备 + if (device_path == nullptr || strlen(device_path) == 0) { + std::cerr << "未找到键盘设备,请确保键盘已连接。" << std::endl; + SetNonCanonicalMode(false); + return; + } + int fd = open(device_path, O_RDONLY); + if (fd < 0) { + std::cerr << "无法打开设备 " << device_path << ",请检查权限或路径是否正确" << std::endl; + SetNonCanonicalMode(false); + return; + } + + struct input_event ev; + char command[16] = {0}; + rclcpp::Time startTime = armNode->get_clock()->now(); + while (rclcpp::ok()) { + int cancel_flag = 0; + ssize_t n = read(fd, &ev, sizeof(ev)); + if (n < (ssize_t)sizeof(ev)) { + continue; // 事件不完整,跳过 + } + // RCLCPP_INFO(armNode->get_logger(), "type: %d, code: %d, value: %d\n", ev.type, ev.code, ev.value); + + // 仅处理键盘事件 + if (ev.type == EV_KEY) { + // ev.code:键码(如KEY_A=30),ev.value:0=释放,1=按下,2=重复(可忽略) + if (ev.value == 1) { // 按键按下 + if (keyToCommand.find(ev.code) == keyToCommand.end()) { + if (ev.code == KEY_Q) { // 按下'q'退出 + std::cout << "退出遥控模式。" << std::endl; + break; + } + continue; // 非定义按键,忽略 + } + command[keyToCommand.at(ev.code)] = 1; + } else if (ev.value == 0) { // 按键释放 + if (keyToCommand.find(ev.code) == keyToCommand.end()) { + continue; // 非定义按键,忽略 + } + command[keyToCommand.at(ev.code)] = 0; + cancel_flag = 1; + } + } + rclcpp::Time nowTime = armNode->get_clock()->now(); + int64_t duration = (nowTime - startTime).nanoseconds(); + if (duration >= 100000000 || cancel_flag) { // 每100ms发送一次命令 + armNode->SendAngleSteppingGoal(command); + startTime = nowTime; + } + } + + // 清理资源 + close(fd); + SetNonCanonicalMode(false); +} + +void KeyboardInputAngleMoving(std::shared_ptr armNode) { + std::string line; + while (rclcpp::ok()) { + std::cout << "请输入: 整数(0(退出)/1(左臂)/2(右臂)),6个float,用','分割,以';'结尾:" << std::endl; + std::getline(std::cin, line, ';'); + std::istringstream ss(line); + std::string token; + int mode; + float values[USED_ARM_DOF]; + bool valid = true; + + // 解析整数 + if (!std::getline(ss, token, ',')) { + valid = false; + } + else { + try { + mode = std::stoi(token); + if (mode != 1 && mode != 2) valid = false; + } catch (...) { + valid = false; + } + } + + // 解析6个float + for (int i = 0; i < USED_ARM_DOF && valid; ++i) { + if (!std::getline(ss, token, ',')) { valid = false; break; } + try { + values[i] = std::stof(token); + } catch (...) { valid = false; } + } + + if (mode == 0) { + std::cout << "退出输入角度模式。" << std::endl; + return; + } + + if (valid) { + if (mode == 1) + armNode->SendAngleMovingGoal(values, LEFT_ARM); + else if (mode == 2) + armNode->SendAngleMovingGoal(values, RIGHT_ARM); + } else { + std::cout << "输入格式错误,请重试。" << std::endl; + } + std::this_thread::sleep_for(std::chrono::seconds(1)); + } +} + +void KeyboardInputPoseMoving(std::shared_ptr armNode) { + std::string line; + while (rclcpp::ok()) { + std::cout << "请输入: 整数(0(退出)/1(左臂)/2(右臂)),7个float,用','分割,以';'结尾:" << std::endl; + std::getline(std::cin, line, ';'); + std::istringstream ss(line); + std::string token; + int mode; + float values[POSE_DIMENSION]; + bool valid = true; + + // 解析整数 + if (!std::getline(ss, token, ',')) { + valid = false; + } + else { + try { + mode = std::stoi(token); + if (mode != 1 && mode != 2) valid = false; + } catch (...) { + valid = false; + } + } + + // 解析6个float + for (int i = 0; i < POSE_DIMENSION && valid; ++i) { + if (!std::getline(ss, token, ',')) { valid = false; break; } + try { + values[i] = std::stof(token); + } catch (...) { valid = false; } + } + + if (mode == 0) { + std::cout << "退出输入pose模式。" << std::endl; + return; + } + + if (valid) { + if (mode == 1) + armNode->SendDirectMovingGoal(values, LEFT_ARM); + else if (mode == 2) + armNode->SendDirectMovingGoal(values, RIGHT_ARM); + } else { + std::cout << "输入格式错误,请重试。" << std::endl; + } + std::this_thread::sleep_for(std::chrono::seconds(1)); + } +} + +void KeyboardInputPoseStepping2(std::shared_ptr armNode) { + std::string line; + auto message = std_msgs::msg::Float64MultiArray(); + message.data.resize(ARM_DOF); + while (rclcpp::ok()) { + std::cout << "请输入: 整数(0(退出)/1(左臂)/2(右臂)/3(停止)),7个float,用','分割,以';'结尾:" << std::endl; + std::getline(std::cin, line, ';'); + std::istringstream ss(line); + std::string token; + int mode; + float values[POSE_DIMENSION]; + bool valid = true; + + // 解析整数 + if (!std::getline(ss, token, ',')) { + valid = false; + } + else { + try { + mode = std::stoi(token); + if (mode != 1 && mode != 2) valid = false; + } catch (...) { + valid = false; + } + } + + // 解析6个float + for (int i = 0; i < POSE_DIMENSION && valid; ++i) { + if (!std::getline(ss, token, ',')) { valid = false; break; } + try { + values[i] = std::stof(token); + } catch (...) { valid = false; } + } + + if (mode == 0) { + std::cout << "退出输入角度模式。" << std::endl; + return; + } + if (mode == 3) { + armNode->StopGoal(); + continue; + } + + if (valid) { + if (mode == 1) + armNode->SendDirectSteppingGoal2(values, LEFT_ARM); + else if (mode == 2) + armNode->SendDirectSteppingGoal2(values, RIGHT_ARM); + } else { + std::cout << "输入格式错误,请重试。" << std::endl; + } + std::this_thread::sleep_for(std::chrono::seconds(1)); + } +} + +void ArmKeyboardNode::StopGoal() +{ + std::cout << "取消当前目标。" << std::endl; + std::lock_guard lock(armAimMutex_); + if (leftArmGoalHandle_ != nullptr && leftCommandId_ != 0) { + client_ptr_->async_cancel_goal(leftArmGoalHandle_); + leftArmGoalHandle_.reset(); + std::cout << "左臂目标已取消。" << std::endl; + } + if (rightArmGoalHandle_ != nullptr && rightCommandId_ != 0) { + client_ptr_->async_cancel_goal(rightArmGoalHandle_); + rightArmGoalHandle_.reset(); + std::cout << "右臂目标已取消。" << std::endl; + } +} + +void ArmKeyboardNode::SendDirectSteppingGoal2(const float *values, int armId) +{ + std::lock_guard lock(armAimMutex_); + int64_t timeStamp = get_clock()->now().nanoseconds(); + auto goal_msg = ArmAction::Goal(); + commandId++; + goal_msg.body_id.body_id = armId; + goal_msg.data_type.action_type = ARM_COMMAND_TYPE_POSE_STEP_ON; // 位置控制 + goal_msg.data_length.data_length = POSE_DIMENSION; + goal_msg.frame_time_stamp = timeStamp; + goal_msg.command_id = commandId; + for (int i = 0; i < POSE_DIMENSION; ++i) { + goal_msg.data_array.push_back(values[i]); + } + auto future = client_ptr_->async_send_goal(goal_msg, goal_options_); + if (armId == LEFT_ARM) { + leftCommandId_ = commandId; + leftArmGoalHandle_ = future.get(); + } else { + rightCommandId_ = commandId; + rightArmGoalHandle_ = future.get(); + } +} + +void ArmKeyboardNode::SendDirectMovingGoal(const float *values, int armId) +{ + std::lock_guard lock(armAimMutex_); + int64_t timeStamp = get_clock()->now().nanoseconds(); + auto goal_msg = ArmAction::Goal(); + commandId++; + goal_msg.body_id.body_id = armId; + goal_msg.data_type.action_type = ARM_COMMAND_TYPE_POSE_DIRECT_MOVE; // 位置控制 + goal_msg.data_length.data_length = POSE_DIMENSION; + goal_msg.frame_time_stamp = timeStamp; + goal_msg.command_id = commandId; + for (int i = 0; i < POSE_DIMENSION; ++i) { + goal_msg.data_array.push_back(values[i]); + } + auto future = client_ptr_->async_send_goal(goal_msg, goal_options_); + if (armId == LEFT_ARM) { + leftCommandId_ = commandId; + leftArmGoalHandle_ = future.get(); + } else { + rightCommandId_ = commandId; + rightArmGoalHandle_ = future.get(); + } +} + +void ArmKeyboardNode::SendAngleMovingGoal(const float *values, int armId) +{ + std::lock_guard lock(armAimMutex_); + int64_t timeStamp = get_clock()->now().nanoseconds(); + auto goal_msg = ArmAction::Goal(); + commandId++; + RCLCPP_INFO(this->get_logger(), "SendAngleMovingGoal id=%ld", commandId); + goal_msg.body_id.body_id = armId; + goal_msg.data_type.action_type = ARM_COMMAND_TYPE_ANGLE_DIRECT_MOVE; // 位置控制 + goal_msg.data_length.data_length = USED_ARM_DOF; + goal_msg.frame_time_stamp = timeStamp; + goal_msg.command_id = commandId; + for (int i = 0; i < USED_ARM_DOF; ++i) { + goal_msg.data_array.push_back(values[i]); + } + auto future = client_ptr_->async_send_goal(goal_msg, goal_options_); + if (armId == LEFT_ARM) { + leftCommandId_ = commandId; + leftArmGoalHandle_ = future.get(); + } else { + rightCommandId_ = commandId; + rightArmGoalHandle_ = future.get(); + } +} + +void KeyboardInputDirectStepping(std::shared_ptr armNode) { + // 设置终端为无缓冲模式 + std::cout << "q:退出,w:左臂控制,e:右臂控制,r:负方向增量,a:x方向移动,s:y方向移动," + << "d:z方向移动,z:rx方向旋转,x:ry方向旋转,c:rz方向旋转,v:rw方向旋转" << std::endl; + SetNonCanonicalMode(true); + + std::string device = find_keyboard_devices(); + std::cout << "找到键盘设备: " << device << std::endl; + const char* device_path = device.c_str(); // 替换为你的键盘设备 + if (device_path == nullptr || strlen(device_path) == 0) { + std::cerr << "未找到键盘设备,请确保键盘已连接。" << std::endl; + SetNonCanonicalMode(false); + return; + } + int fd = open(device_path, O_RDONLY); + if (fd < 0) { + std::cerr << "无法打开设备 " << device_path << ",请检查权限或路径是否正确" << std::endl; + SetNonCanonicalMode(false); + return; + } + + struct input_event ev; + char command[16] = {0}; + rclcpp::Time startTime = armNode->get_clock()->now(); + while (rclcpp::ok()) { + int cancel_flag = 0; + ssize_t n = read(fd, &ev, sizeof(ev)); + if (n < (ssize_t)sizeof(ev)) { + continue; // 事件不完整,跳过 + } + // RCLCPP_INFO(armNode->get_logger(), "type: %d, code: %d, value: %d\n", ev.type, ev.code, ev.value); + + // 仅处理键盘事件 + if (ev.type == EV_KEY) { + // ev.code:键码(如KEY_A=30),ev.value:0=释放,1=按下,2=重复(可忽略) + if (ev.value == 1) { // 按键按下 + if (keyToCommand.find(ev.code) == keyToCommand.end()) { + if (ev.code == KEY_Q) { // 按下'q'退出 + std::cout << "退出遥控模式。" << std::endl; + break; + } + continue; // 非定义按键,忽略 + } + command[keyToCommand.at(ev.code)] = 1; + } else if (ev.value == 0) { // 按键释放 + if (keyToCommand.find(ev.code) == keyToCommand.end()) { + continue; // 非定义按键,忽略 + } + command[keyToCommand.at(ev.code)] = 0; + cancel_flag = 1; + } + } + rclcpp::Time nowTime = armNode->get_clock()->now(); + int64_t duration = (nowTime - startTime).nanoseconds(); + if (duration >= 100000000 || cancel_flag) { // 每100ms发送一次命令 + armNode->SendDirectSteppingGoal(command); + startTime = nowTime; + } + } + + // 清理资源 + close(fd); + SetNonCanonicalMode(false); +} + +static void ListenInputThread(std::shared_ptr armNode) { + std::string line; + auto message = std_msgs::msg::Float64MultiArray(); + message.data.resize(ARM_DOF); + while (rclcpp::ok()) { + std::cout << "请输入选择控制模式,0:退出,1:移动至目标角度,2:移动至目标位置,3:持续旋转角度,4:持续往某个方向移动,以';'结尾:" << std::endl; + std::getline(std::cin, line, ';'); + int mode = 0; + try { + mode = std::stoi(line); + } catch (...) { + std::cout << "输入格式错误,请重试。" << std::endl; + continue; + } + + switch (mode) { + case 0: + std::cout << "退出输入监听线程。" << std::endl; + armNode->exit_flag = true; + return; + case 1: + KeyboardInputAngleMoving(armNode); + break; + case 2: + KeyboardInputPoseMoving(armNode); + break; + case 3: + KeyboardInputAngleStepping(armNode); + std::getline(std::cin, line, 'q'); + break; + case 4: + KeyboardInputPoseStepping2(armNode); + break; + case 5: + KeyboardInputPoseStepping2(armNode); + break; + default: + if (mode != 0) { + std::cout << "无效选择,请重试。" << std::endl; + } + break; + } + } +} + +ArmKeyboardNode::ArmKeyboardNode() : Node("arm_keyboard_node") +{ + for (int i = 0; i < USED_ARM_DOF; ++i) { + leftArmAngleAim_[i] = 0.0; + rightArmAngleAim_[i] = 0.0; + } + leftCommandId_ = 0; + rightCommandId_ = 0; + leftArmAimPub_ = this->create_publisher("left_arm_command", 10); + rightArmAimPub_ = this->create_publisher("right_arm_command", 10); + exit_flag = false; + this->client_ptr_ = rclcpp_action::create_client( + this, + "ArmAction"); + goal_options_.goal_response_callback = + std::bind(&ArmKeyboardNode::goal_response_callback, this, _1); + goal_options_.feedback_callback = + std::bind(&ArmKeyboardNode::feedback_callback, this, _1, _2); + goal_options_.result_callback = + std::bind(&ArmKeyboardNode::result_callback, this, _1); +} + +ArmKeyboardNode::~ArmKeyboardNode() +{ + if (inputThread_.joinable()) { + inputThread_.join(); // 或 join(),视你的需求 + } + rightArmAimPub_.reset(); + leftArmAimPub_.reset(); +} + +void ArmKeyboardNode::goal_response_callback(GoalHandleArm::SharedPtr goal_handle) +{ + if (!goal_handle) { + RCLCPP_ERROR(this->get_logger(), "Goal was rejected by server"); + } else { + RCLCPP_INFO(this->get_logger(), "Goal accepted by server, waiting for result"); + } +} + +void ArmKeyboardNode::feedback_callback( + GoalHandleArm::SharedPtr goal_handle, + const std::shared_ptr feedback) +{ + if (!goal_handle || !feedback) { + RCLCPP_INFO(this->get_logger(), "feedback received err."); + } +} + +void ArmKeyboardNode::result_callback(const GoalHandleArm::WrappedResult & result) +{ + std::unique_lock lock(rw_mutex_); + int64_t command_id = result.result->command_id; + if (command_id == leftCommandId_) { + leftCommandId_ = 0; + leftArmGoalHandle_ = nullptr; + } else if (command_id == rightCommandId_) { + rightCommandId_ = 0; + rightArmGoalHandle_ = nullptr; + } else { + RCLCPP_ERROR(this->get_logger(), "Unknown command id in result: %ld", command_id); + return; + } + switch (result.code) { + case rclcpp_action::ResultCode::SUCCEEDED: + RCLCPP_INFO(this->get_logger(), "Goal was succeeded, command id: %ld", command_id); + break; + case rclcpp_action::ResultCode::ABORTED: + RCLCPP_ERROR(this->get_logger(), "Goal was aborted, command id: %ld", command_id); + return; + case rclcpp_action::ResultCode::CANCELED: + RCLCPP_ERROR(this->get_logger(), "Goal was canceled, command id: %ld", command_id); + return; + default: + RCLCPP_ERROR(this->get_logger(), "Unknown result code, command id: %ld", command_id); + return; + } +} + +int directCommandMap[POSE_DIMENSION] = {0, 1, 2, 6, 7, 8, 9}; + +void ArmKeyboardNode::SendDirectSteppingGoal(const char *command) +{ + std::unique_lock lock(rw_mutex_); + std::string commandStr = "command: "; + for (int i = 0; i < 16; ++i) { + if (command[i]) { + commandStr += std::to_string(i) + " "; + } + } + RCLCPP_INFO(this->get_logger(), "%s", commandStr.c_str()); + if (client_ptr_ == nullptr) { + RCLCPP_ERROR(this->get_logger(), "Action client not initialized"); + return; + } + if (!client_ptr_->action_server_is_ready()) { + RCLCPP_ERROR(this->get_logger(), "Action server not ready"); + return; + } + auto goal_msg = ArmAction::Goal(); + int commandValueBitMap = 0; + double speedadd = 0.01; + if (command[14]) { + speedadd = -0.01; + } + + goal_msg.data_type.action_type = ARM_COMMAND_TYPE_POSE_STEP_ON; // 位置控制 + goal_msg.data_length.data_length = POSE_DIMENSION; + goal_msg.command_id = commandId; + for (int i = 0; i < POSE_DIMENSION; ++i) { + if (command[directCommandMap[i]]) { + goal_msg.data_array.push_back(speedadd); + commandValueBitMap |= (1 << i); + } else { + goal_msg.data_array.push_back(0.0); + } + } + + if (command[12] && leftDirectCommand_!= commandValueBitMap) { + commandId++; + goal_msg.body_id.body_id = LEFT_ARM; + leftDirectCommand_ = commandValueBitMap; + if (leftArmGoalHandle_ != nullptr && leftCommandId_ != 0) { + RCLCPP_INFO(this->get_logger(), "cancel left arm goal. command id: %ld", leftCommandId_); + client_ptr_->async_cancel_goal(leftArmGoalHandle_); + leftArmGoalHandle_.reset(); + } else if (rightArmGoalHandle_ != nullptr && rightCommandId_ != 0) { + RCLCPP_INFO(this->get_logger(), "cancel right arm goal. command id: %ld", rightCommandId_); + client_ptr_->async_cancel_goal(rightArmGoalHandle_); + rightArmGoalHandle_.reset(); + } + + if (commandValueBitMap != 0) { + auto future = client_ptr_->async_send_goal(goal_msg, goal_options_); + leftCommandId_ = commandId; + leftArmGoalHandle_ = future.get(); + RCLCPP_INFO(this->get_logger(), "send left arm goal, command id: %ld", commandId); + } + } else if (command[13] && rightDirectCommand_!= commandValueBitMap) { + commandId++; + goal_msg.body_id.body_id = RIGHT_ARM; + rightDirectCommand_ = commandValueBitMap; + if (rightArmGoalHandle_ != nullptr && rightCommandId_ != 0) { + RCLCPP_INFO(this->get_logger(), "cancel right arm goal. command id: %ld", rightCommandId_); + client_ptr_->async_cancel_goal(rightArmGoalHandle_); + rightArmGoalHandle_.reset(); + } else if (leftArmGoalHandle_ != nullptr && leftCommandId_ != 0) { + RCLCPP_INFO(this->get_logger(), "cancel left arm goal. command id: %ld", leftCommandId_); + client_ptr_->async_cancel_goal(leftArmGoalHandle_); + leftArmGoalHandle_.reset(); + } + + if (commandValueBitMap != 0) { + auto future = client_ptr_->async_send_goal(goal_msg, goal_options_); + rightCommandId_ = commandId; + rightArmGoalHandle_ = future.get(); + RCLCPP_INFO(this->get_logger(), "send right arm goal, command id: %ld", commandId); + } + } else { + RCLCPP_ERROR(this->get_logger(), "No arm selected"); + return; + } +} + +int actionChange[8] = {KEEP_ACTION, NEW_ACTION, KEEP_ACTION, NEW_ACTION, + STOP_ACTION, NEW_ACTION, NEW_ACTION, NEW_ACTION}; + +void ArmKeyboardNode::SendAngleSteppingGoal(const char *command) { + std::unique_lock lock(rw_mutex_); + std::string commandStr = "command: "; + for (int i = 0; i < 16; ++i) { + if (command[i]) { + commandStr += std::to_string(i) + " "; + } + } + RCLCPP_INFO(this->get_logger(), "%s", commandStr.c_str()); + if (client_ptr_ == nullptr) { + RCLCPP_ERROR(this->get_logger(), "Action client not initialized"); + return; + } + if (!client_ptr_->action_server_is_ready()) { + RCLCPP_ERROR(this->get_logger(), "Action server not ready"); + return; + } + float speedadd = 0.02; + if (command[12]) { + speedadd = -0.02; + } + int rightArmMove = 0; + int leftArmMove = 0; + int rightArmStop = 0; + int leftArmStop = 0; + int rightArmNew = 0; + int leftArmNew = 0; + int rightArmKeep = 0; + int leftArmKeep = 0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + if (command[i]) { + if (fabs(leftArmAngleAim_[i] + speedadd) < 0.1) { + leftArmAngleAim_[i] += speedadd; + leftArmNew = 1; + } else { + leftArmKeep = 1; + } + } else { + if (leftArmAngleAim_[i] != 0.0f) { + leftArmAngleAim_[i] = 0; + leftArmStop = 1; + } + } + if (command[i + USED_ARM_DOF]) { + if (fabs(rightArmAngleAim_[i] + speedadd) < 0.1) { + rightArmAngleAim_[i] += speedadd; + rightArmNew = 1; + } else { + rightArmKeep = 1; + } + } else { + if (rightArmAngleAim_[i] != 0.0f) { + rightArmAngleAim_[i] = 0; + rightArmStop = 1; + } + } + } + + leftArmMove = actionChange[leftArmNew | (leftArmStop << 2) | (leftArmKeep << 1)]; + rightArmMove = actionChange[rightArmNew | (rightArmStop << 2) | (rightArmKeep << 1)]; + + if (leftArmMove != KEEP_ACTION) { + if (leftArmGoalHandle_ != nullptr && leftCommandId_ != 0) { + RCLCPP_INFO(this->get_logger(), "cancel left arm goal. command id: %ld", leftCommandId_); + client_ptr_->async_cancel_goal(leftArmGoalHandle_); + leftArmGoalHandle_.reset(); + } + if ((leftArmMove & NEW_ACTION) != 0) { + auto goal_msg = ArmAction::Goal(); + commandId++; + leftCommandId_ = commandId; + goal_msg.body_id.body_id = LEFT_ARM; + goal_msg.data_type.action_type = ARM_COMMAND_TYPE_ANGLE_STEP_ON; // 位置控制 + goal_msg.data_length.data_length = USED_ARM_DOF; + goal_msg.command_id = commandId; + for (int i = 0; i < USED_ARM_DOF; ++i) { + goal_msg.data_array.push_back(leftArmAngleAim_[i]); + } + auto future = client_ptr_->async_send_goal(goal_msg, goal_options_); + leftArmGoalHandle_ = future.get(); + RCLCPP_INFO(this->get_logger(), "send left arm goal, command id: %ld", commandId); + } + } + if (rightArmMove != KEEP_ACTION) { + if (rightArmGoalHandle_ != nullptr && rightCommandId_ != 0) { + RCLCPP_INFO(this->get_logger(), "cancel right arm goal. command id: %ld", rightCommandId_); + client_ptr_->async_cancel_goal(rightArmGoalHandle_); + rightArmGoalHandle_.reset(); + } + if ((rightArmMove & NEW_ACTION) != 0) { + auto goal_msg = ArmAction::Goal(); + commandId++; + rightCommandId_ = commandId; + goal_msg.body_id.body_id = RIGHT_ARM; + goal_msg.data_type.action_type = ARM_COMMAND_TYPE_ANGLE_STEP_ON; // 位置控制 + goal_msg.data_length.data_length = USED_ARM_DOF; + goal_msg.command_id = commandId; + + for (int i = 0; i < USED_ARM_DOF; ++i) { + goal_msg.data_array.push_back(rightArmAngleAim_[i]); + } + auto future = client_ptr_->async_send_goal(goal_msg, goal_options_); + rightArmGoalHandle_ = future.get(); + RCLCPP_INFO(this->get_logger(), "send right arm goal, command id: %ld", commandId); + } + } +} + +int main(int argc, char *argv[]) +{ + /*std::vector polyA = {Vector3d(2,0,0), Vector3d(4,0,0), Vector3d(2,2,0), Vector3d(4,2,0), + Vector3d(2,0,2), Vector3d(4,0,2), Vector3d(2,2,2), Vector3d(4,2,2)}; + std::vector polyB = {Vector3d(3,1,1), Vector3d(5,1,1), Vector3d(3,3,1), Vector3d(5,3,1), + Vector3d(3,1,3), Vector3d(5,1,3), Vector3d(3,3,3), Vector3d(5,3,3)}; + OBB obbA = gjk_interface::createOBBFromVertices(polyA, 2, 2, 2); + OBB obbB = gjk_interface::createOBBFromVertices(polyB, 2, 2, 2); + bool inCollisionOBB = gjk_interface::checkOBBCollision(obbA, obbB); + if (inCollisionOBB) { + printf("dect poly A and B collision\n"); + } else { + printf("dect poly A and B safe\n"); + } + + polyA = {Vector3d(2,0,0), Vector3d(4,0,0), Vector3d(2,2,0), Vector3d(4,2,0), + Vector3d(2,0,2), Vector3d(4,0,2), Vector3d(2,2,2), Vector3d(4,2,2)}; + polyB = {Vector3d(3.99,0,0), Vector3d(5.99,0,0), Vector3d(3.99,2,0), Vector3d(5.99,2,0), + Vector3d(3.99,0,2), Vector3d(5.99,0,2), Vector3d(3.99,2,2), Vector3d(5.99,2,2)}; + obbA = gjk_interface::createOBBFromVertices(polyA, 2, 2, 2); + obbB = gjk_interface::createOBBFromVertices(polyB, 2, 2, 2); + inCollisionOBB = gjk_interface::checkOBBCollision(obbA, obbB); + if (inCollisionOBB) { + printf("dect poly A and B collision\n"); + } else { + printf("dect poly A and B safe\n"); + }*/ + + rclcpp::init(argc, argv); + rclcpp::Node::SharedPtr node = std::make_shared(); + std::shared_ptr armNode = std::dynamic_pointer_cast(node); + // 启动输入监听线程 + inputThread_ = std::thread(ListenInputThread, armNode); + while (rclcpp::ok() && !armNode->exit_flag) { + rclcpp::spin_some(node); // 处理所有待处理的事件 + std::this_thread::sleep_for(std::chrono::milliseconds(10)); // 短暂休眠,降低CPU占用 + } + rclcpp::shutdown(); + + return 0; +} diff --git a/common_msg/CMakeLists.txt b/common_msg/CMakeLists.txt new file mode 100644 index 0000000..9f6c5ef --- /dev/null +++ b/common_msg/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 3.8) +project(common_msg) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + "msg/ArmCommnd.msg" +) + +ament_package() diff --git a/common_msg/LICENSE b/common_msg/LICENSE new file mode 100644 index 0000000..d645695 --- /dev/null +++ b/common_msg/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. diff --git a/common_msg/msg/ArmCommnd.msg b/common_msg/msg/ArmCommnd.msg new file mode 100644 index 0000000..4eaac84 --- /dev/null +++ b/common_msg/msg/ArmCommnd.msg @@ -0,0 +1,5 @@ +int8 body_id +int8 data_type +int16 data_length +int32 command_id +float64[] data_array \ No newline at end of file diff --git a/common_msg/package.xml b/common_msg/package.xml new file mode 100644 index 0000000..44400ee --- /dev/null +++ b/common_msg/package.xml @@ -0,0 +1,17 @@ + + + + common_msg + 0.0.0 + common_msg + zj + Apache-2.0 + + ament_cmake + rosidl_default_generators + rosidl_default_runtime + rosidl_interface_packages + + ament_cmake + + diff --git a/gjk_interface/CMakeLists.txt b/gjk_interface/CMakeLists.txt new file mode 100644 index 0000000..347c954 --- /dev/null +++ b/gjk_interface/CMakeLists.txt @@ -0,0 +1,42 @@ +cmake_minimum_required(VERSION 3.8) +project(gjk_interface) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() +add_compile_options(-g) + +find_package(ament_cmake REQUIRED) +find_package(eigen3_cmake_module REQUIRED) +find_package(Eigen3 REQUIRED) # 查找Eigen3库 + +add_library(${PROJECT_NAME} SHARED + src/gjk_interface.cpp +) + +ament_target_dependencies(gjk_interface + Eigen3 +) + +target_include_directories(${PROJECT_NAME} + PUBLIC + $ + $ +) + +install(TARGETS ${PROJECT_NAME} + EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install( + DIRECTORY include/ + DESTINATION include +) + +ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) +ament_export_include_directories(include) + +ament_package() diff --git a/gjk_interface/LICENSE b/gjk_interface/LICENSE new file mode 100644 index 0000000..d645695 --- /dev/null +++ b/gjk_interface/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. diff --git a/gjk_interface/include/gjk_interface.hpp b/gjk_interface/include/gjk_interface.hpp new file mode 100644 index 0000000..eafe501 --- /dev/null +++ b/gjk_interface/include/gjk_interface.hpp @@ -0,0 +1,27 @@ +#ifndef GJK_INTERFACE_HPP +#define GJK_INTERFACE_HPP + +#include +#include + +typedef enum { + COLLISION_RESULT_NO_COLLISION = 0, + COLLISION_RESULT_COLLISION = 1, + COLLISION_RESULT_ERROR = -1 +} CollisionResultE; + +struct OBB { + Eigen::Vector3d center; // 中心 + Eigen::Vector3d axis[3]; // 3条正交的棱边方向轴(单位向量) + double halfExtent[3]; // 沿各轴的半长(从中心到面的距离) +}; + +namespace gjk_interface { + bool gjkCollisionJudge(const std::vector& polyA, const std::vector& polyB); + OBB createOBBFromVertices(const std::vector& vertices, + const float length, const float width, const float height); + bool checkOBBCollision(const OBB &obb1, const OBB &obb2); + +} // namespace gjk_interface + +#endif // GJK_INTERFACE_HPP \ No newline at end of file diff --git a/gjk_interface/package.xml b/gjk_interface/package.xml new file mode 100644 index 0000000..e8195e5 --- /dev/null +++ b/gjk_interface/package.xml @@ -0,0 +1,16 @@ + + + + gjk_interface + 0.0.0 + gjk_interface + zj + Apache-2.0 + + ament_cmake + Eigen3 + + + ament_cmake + + diff --git a/gjk_interface/src/gjk_interface.cpp b/gjk_interface/src/gjk_interface.cpp new file mode 100644 index 0000000..1a15b53 --- /dev/null +++ b/gjk_interface/src/gjk_interface.cpp @@ -0,0 +1,249 @@ +#include "math.h" +#include "gjk_interface.hpp" + +#define POLY_SIMPLIFY_MAX_SIZE 4 +using namespace Eigen; + +namespace gjk_interface { + const Vector3d support(const std::vector& poly, const Vector3d& dir) + { + float maxDot = -INFINITY; + Vector3d supportPoint; + + for (const Vector3d& p : poly) { + float dot = p.dot(dir); + if (dot > maxDot) { + maxDot = dot; + supportPoint = p; + } + } + + return supportPoint; + } + + Vector3d supportMinkowski(const std::vector& polyA, const std::vector& polyB, Vector3d& dir) + { + Vector3d simplexPoint = support(polyA, dir); + const Vector3d oppositeDir = dir * -1; + simplexPoint = simplexPoint - support(polyB, oppositeDir); + return simplexPoint; + } + + Vector3d checkLineSegment3D(const Vector3d& v0, const Vector3d& v1) { + Vector3d a = v1 - v0; // 线段方向向量 + Vector3d b = -v1; // 从v1到原点的向量 + + float aDotA = a.dot(a); + Vector3d bParallel = a * (a.dot(b) / aDotA); // 平行投影 + Vector3d bPerp = b - bParallel; // 垂直投影(新方向) + + return bPerp; + } + + Vector3d GetNormalToOri(const Vector3d& a, const Vector3d& b, const Vector3d& c) { + Vector3d ab = b - a; + Vector3d ac = c - a; + Vector3d ad = -a; + + Vector3d n_initial = ab.cross(ac); + Vector3d n_outer = (n_initial.dot(ad) < 0) ? -n_initial : n_initial; + return n_outer; + } + + Vector3d GetDir(const std::vector& simplex) { + if (simplex.size() == 1) { + return -simplex[0]; + } else if (simplex.size() == 2) { + return checkLineSegment3D(simplex[0], simplex[1]); + } else if (simplex.size() == 3) { + return GetNormalToOri(simplex[0], simplex[1], simplex[2]); + } + return Vector3d(0, 0, 0); + } + + bool CheckTetrahedronHaveZero(const std::vector& simplex) { + Vector3d A = simplex[0]; + Vector3d B = simplex[1]; + Vector3d C = simplex[2]; + Vector3d D = simplex[3]; // 最新点(面ABC的对 + // 构造线性方程组 Ax = b(求解alpha, beta, gamma) + Matrix3d mat; + mat.col(0) = A - D; // x1-x4, y1-y4, z1-z4 + mat.col(1) = B - D; // x2-x4, y2-y4, z2-z4 + mat.col(2) = C - D; // x3-x4, y3-y4, z3-z4 + Vector3d b = -D; // -x4, -y4, -z4 + + // 求解方程组:mat * [alpha; beta; gamma] = b + if (mat.determinant() == 0) { + return true; + } + Vector3d x = mat.inverse() * b; + float alpha = x(0), beta = x(1), gamma = x(2); + float delta = 1 - alpha - beta - gamma; + + // 判定4个权重是否均为正(允许1e-6误差) + const float eps = 1e-6; + return (alpha > eps) && (beta > eps) && (gamma > eps) && (delta > eps); + } + + bool CheckTetrahedronHaveZero2(const std::vector& simplex) { + Vector3d A = simplex[0]; + Vector3d B = simplex[1]; + Vector3d C = simplex[2]; + Vector3d D = simplex[3]; // 最新点(面ABC的对 + // 构造线性方程组 Ax = b(求解alpha, beta, gamma) + auto scalar_triple = [](const Vector3d& a, const Vector3d& b, const Vector3d& c) { + return a.dot(b.cross(c)); // Eigen封装了叉积和点积,底层运算与手动计算一致 + }; + + double v0 = scalar_triple(B, C, D); + double v1 = scalar_triple(A, C, D); + double v2 = scalar_triple(A, B, D); + double v3 = scalar_triple(A, B, C); + + // 判断所有符号是否一致(均正或均负) + bool all_positive = (v0 > 0) && (v1 > 0) && (v2 > 0) && (v3 > 0); + bool all_negative = (v0 < 0) && (v1 < 0) && (v2 < 0) && (v3 < 0); + + return all_positive || all_negative; + } + + bool gjkCollisionJudge(const std::vector& polyA, const std::vector& polyB) + { + // 初始搜索方向(从A中心指向B中心) + Vector3d centerA(0, 0, 0), centerB(0, 0, 0); + for (const auto& p : polyA) { + centerA = centerA + p; + } + for (const auto& p : polyB) { + centerB = centerB + p; + } + centerA = centerA / polyA.size(); + centerB = centerB / polyA.size(); + Vector3d dir = centerB - centerA; + + // 初始化单纯形 + std::vector simplex; + Vector3d newPoint = supportMinkowski(polyA, polyB, dir); + simplex.push_back(newPoint); + + int maxIndex = 3; + while (true) { + dir = GetDir(simplex); + if (dir.dot(dir) < 1e-6) { + return true; + } + newPoint = supportMinkowski(polyA, polyB, dir); + if (newPoint.dot(newPoint) < 1e-6) { + return true; + } + if (newPoint.dot(dir) < -(1e-6)) { + return false; + } + simplex.push_back(newPoint); + if (simplex.size() == POLY_SIMPLIFY_MAX_SIZE) { + bool haveZero = CheckTetrahedronHaveZero2(simplex); + if (haveZero) { + return true; + } else { + float maxLength = 0; + for (size_t i = 0; i < POLY_SIMPLIFY_MAX_SIZE; i++) { + Vector3d simplexPoint = simplex[i]; + float newLength = simplexPoint.dot(simplexPoint); + if (maxLength < newLength) { + maxLength = newLength; + maxIndex = i; + } + } + simplex.erase(simplex.begin() + maxIndex); + } + } + } + + return false; + } + + // 从8个顶点提取OBB参数 + OBB createOBBFromVertices(const std::vector& vertices, + const float length, const float width, const float height) { + if (vertices.size() != 8) { + throw std::invalid_argument("OBB创建失败:必须输入8个顶点"); + } + + OBB obb; + + obb.center = (vertices[1] + vertices[2] + vertices[4] - vertices[0]) * (1.0 / 2.0); + + // 正交化(格拉姆-施密特过程),确保3条轴正交 + obb.axis[0] = (vertices[1] - vertices[0]).normalized(); + obb.axis[1] = (vertices[2] - vertices[0]).normalized(); + obb.axis[2] = (vertices[4] - vertices[0]).normalized(); + + obb.halfExtent[0] = length * (1.0 / 2.0); + obb.halfExtent[1] = width * (1.0 / 2.0); + obb.halfExtent[2] = height * (1.0 / 2.0); + + return obb; + } + + // 计算OBB在指定轴上的投影范围(min, max) + std::pair projectOBB(const OBB& obb, const Vector3d& axis) { + // OBB中心在轴上的投影 + double centerProj = obb.center.dot(axis); + // OBB沿轴的总投影长度(半长在轴上的投影之和) + double totalExtent = 0.0; + for (int i = 0; i < 3; ++i) { + totalExtent += obb.halfExtent[i] * fabs(obb.axis[i].dot(axis)); + } + return { centerProj - totalExtent, centerProj + totalExtent }; + } + + // 判断两个投影范围是否重叠 + bool areProjectionsOverlapping(double aMin, double aMax, double bMin, double bMax) { + return !(aMax < bMin - 1e-6 || bMax < aMin - 1e-6); // 1e-6为浮点误差容限 + } + + // OBB碰撞检测主函数(输入:两个长方体的8个顶点,共16个) + bool checkOBBCollision(const OBB &obb1, const OBB &obb2) { + + // 2. 定义所有需要检查的分离轴(共15条) + std::vector separationAxes; + + // 2.3 两个OBB轴的两两叉积(3×3=9条) + for (int i = 0; i < 3; ++i) { + for (int j = 0; j < 3; ++j) { + Vector3d crossAxis = obb1.axis[i].cross(obb2.axis[j]); + if (crossAxis.dot(crossAxis) > 1e-6) { // 排除零向量(轴平行时叉积为零 + Vector3d crossAxisNormalized = crossAxis.normalized(); + auto [aMin, aMax] = projectOBB(obb1, crossAxisNormalized); + auto [bMin, bMax] = projectOBB(obb2, crossAxisNormalized); + if (!areProjectionsOverlapping(aMin, aMax, bMin, bMax)) { + // 找到分离轴,判定为不碰撞 + return false; + } + } + } + } + // 2.1 第一个OBB的3条轴 + for (int i = 0; i < 3; ++i) { + auto [aMin, aMax] = projectOBB(obb1, obb1.axis[i]); + auto [bMin, bMax] = projectOBB(obb2, obb1.axis[i]); + if (!areProjectionsOverlapping(aMin, aMax, bMin, bMax)) { + // 找到分离轴,判定为不碰撞 + return false; + } + } + // 2.2 第二个OBB的3条轴 + for (int i = 0; i < 3; ++i) { + auto [aMin, aMax] = projectOBB(obb1, obb2.axis[i]); + auto [bMin, bMax] = projectOBB(obb2, obb2.axis[i]); + if (!areProjectionsOverlapping(aMin, aMax, bMin, bMax)) { + // 找到分离轴,判定为不碰撞 + return false; + } + } + + // 所有轴均重叠,判定为碰撞 + return true; + } +} diff --git a/include/arm_define.h b/include/arm_define.h new file mode 100644 index 0000000..73f2855 --- /dev/null +++ b/include/arm_define.h @@ -0,0 +1,66 @@ +#ifndef ARM_DEFINE_H +#define ARM_DEFINE_H + +#define USED_ARM_DOF (6) +#define GOAL_DATA_LENGTH (7) +#define USED_OTHER_DOF (17) + +#define MAX_ARM_GOAL_COUNT 16 +#define MAX_TRAJECTORY_HISTORY 64 +#define ARM_FOLLOWING_PERIOD (5e6) //ns == 5ms +#define ARM_FOLLOWING_CHECKING_STEP (4) +#define ARM_FOLLOWING_CHECKING (ARM_FOLLOWING_PERIOD * ARM_FOLLOWING_CHECKING_STEP) //ns == 20ms +#define GET_FUNC_LINE_STR() \ + (std::string(__func__ ) + ":" + std::to_string(__LINE__)) + +#define LEFT_ARM_IP_ADDRESS "192.168.2.2" +#define RIGHT_ARM_IP_ADDRESS "192.168.2.18" +#define ARM_IP_PORT (8080) + +#define TRAJECTORY_COMPLETE 1 +#define TRAJECTORY_ONGOING 0 +#define TRAJECTORY_ERROR -1 + +typedef enum { + ARM_COMMAND_TYPE_ANGLE_STEP_ON = 0, + ARM_COMMAND_TYPE_POSE_STEP_ON, + ARM_COMMAND_TYPE_ANGLE_DIRECT_MOVE, + ARM_COMMAND_TYPE_POSE_DIRECT_MOVE, + ARM_COMMAND_TYPE_ERR +} ArmCommandTypeE; + +typedef enum { + POSE_POSITION_X = 0, + POSE_POSITION_Y, + POSE_POSITION_Z, + POSE_QUATERNION_X, + POSE_QUATERNION_Y, + POSE_QUATERNION_Z, + POSE_QUATERNION_W, + POSE_DIMENSION, // should be 7 +} PoseDimensionE; + +typedef enum { + LEFT_ARM = 0, + RIGHT_ARM, + ARM_ID_ERR +} ArmIdE; + +typedef enum { + GOAL_TYPE_MOVING = 0, + GOAL_TYPE_STEPPING, + GOAL_TYPE_POSE_STEPPING, + GOAL_TYPE_ERROR +} GoalTypeE; + +typedef enum { + OK = 0, + UNKNOWN_ERR = -1, + ARM_NOW_FORCE_MOVING = -2, + ARM_COLLISION = -3, + ARM_AIM_CANNOT_REACH = -4, + ARM_NOW_NO_GOAL = -5, + ARM_GOAL_CANCELLED = -6, +} ErrCodeE; + +#endif // ARM_DEFINE_H \ No newline at end of file diff --git a/include/rm_define.h b/include/rm_define.h new file mode 100644 index 0000000..97c77fc --- /dev/null +++ b/include/rm_define.h @@ -0,0 +1,1035 @@ +#ifndef RM_DEFINE_H +#define RM_DEFINE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#include + +#define ARM_DOF 7 +#define M_PI 3.14159265358979323846 + +#define RM_MOVE_NBLOCK 0 ///<机械臂运动设置,非阻塞模式 +#define RM_MOVE_MULTI_BLOCK 1 ///<机械臂运动设置,多线程阻塞模式 +static inline int RM_MOVE_SINGLE_BLOCK(int timeout){return timeout;} ///<机械臂运动设置,单线程阻塞模式超时时间 + +/** + * @brief 线程模式 + * @ingroup Init_Class + */ +typedef enum { + RM_SINGLE_MODE_E, ///< 单线程模式,单线程非阻塞等待数据返回 + RM_DUAL_MODE_E, ///< 双线程模式,增加接收线程监测队列中的数据 + RM_TRIPLE_MODE_E, ///< 三线程模式,在双线程模式基础上增加线程监测UDP接口数据 +}rm_thread_mode_e; + +/** + * @brief 机械臂型号 + */ +typedef enum{ + RM_MODEL_RM_65_E, ///< RM_65 + RM_MODEL_RM_75_E, ///< RM_75 + RM_MODEL_RM_63_I_E, ///< RML_63I(已弃用) + RM_MODEL_RM_63_II_E, ///< RML_63II + RM_MODEL_RM_63_III_E, ///< RML_63III + RM_MODEL_ECO_65_E, ///< ECO_65 + RM_MODEL_ECO_62_E, ///< ECO_62 + RM_MODEL_GEN_72_E, ///< GEN_72 + RM_MODEL_ECO_63_E, ///< ECO63 + RM_MODEL_UNIVERSAL_E, ///< 通用型 + RM_MODEL_ZM7L_E, ///< ZM7L, + RM_MODEL_ZM7R_E, ///< ZM7R, + RM_MODEL_RXL75_E, ///< 人型机器人左臂 + RM_MODEL_RXR75_E, ///< 人型机器人右臂 +}rm_robot_arm_model_e; + +/** + * @brief 机械臂末端力传感器版本 + * @ingroup Algo + */ +typedef enum{ + RM_MODEL_RM_B_E, ///< 标准版 + RM_MODEL_RM_ZF_E, ///< 一维力版 + RM_MODEL_RM_SF_E, ///< 六维力版 + RM_MODEL_RM_ISF_E, ///< 一体化六维力版 +}rm_force_type_e; + +/** + * @brief 事件类型 + * @ingroup Init_Class + */ +typedef enum +{ + RM_NONE_EVENT_E, ///< 无事件 + RM_CURRENT_TRAJECTORY_STATE_E, ///< 当前轨迹到位 + RM_PROGRAM_RUN_FINISH_E, ///< 在线编程运行结束 +} rm_event_type_e; + +/** + * @brief 事件信息 + * @ingroup Init_Class + */ +typedef struct +{ + int handle_id; ///< 返回消息的机械臂id + rm_event_type_e event_type; ///< 事件类型,包含无事件、当前轨迹到位、在线编程运行结束 + bool trajectory_state; ///< 当前轨迹到位状态 + int device; ///< 到位设备,0:关节 1:夹爪 2:灵巧手 3:升降机构 4:扩展关节 其他:保留 + int trajectory_connect; ///< 是否连接下一条轨迹,0:全部到位,1:连接下一条轨迹 + int program_id; ///< 运行结束的在线编程程序id +}rm_event_push_data_t; + +/** + * @brief 机械臂当前规划类型 + * + */ +typedef enum +{ + RM_NO_PLANNING_E, ///< 无规划 + RM_JOINT_SPACE_PLANNING_E, ///< 关节空间规划 + RM_CARTESIAN_LINEAR_PLANNING_E, ///< 笛卡尔空间直线规划 + RM_CARTESIAN_ARC_PLANNING_E, ///< 笛卡尔空间圆弧规划 + RM_SPLINE_CURVE_MOTION_PLANNING_E, ///< 样条曲线运动规划 + RM_TRAJECTORY_REPLAY_PLANNING_E, ///< 示教轨迹复现规划 +}rm_arm_current_trajectory_e; + +typedef struct +{ + int joint_speed; ///< 关节速度。 + int lift_state; ///< 升降关节信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int expand_state; ///< 扩展关节信息(升降关节和扩展关节为二选一,优先显示升降关节)1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int hand_state; ///< 灵巧手状态。1:上报;0:关闭上报;-1:不设置,保持之前的状态(1.7.0版本无这个) + int arm_current_status; ///< 机械臂当前状态。1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int aloha_state; ///< aloha主臂状态是否上报。1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int plus_base; ///< 末端设备基础信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态 + int plus_state; ///< 末端设备实时信息。1:上报;0:关闭上报;-1:不设置,保持之前的状态 +}rm_udp_custom_config_t; + +/** + * @brief 机械臂主动上报接口配置 + * @ingroup UdpConfig + */ +typedef struct { + int cycle; ///< 广播周期,5ms的倍数 + bool enable; ///< 使能,是否主动上报 + int port; ///< 广播的端口号 + int force_coordinate; ///< 系统外受力数据的坐标系,-1不支持力传感器 0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系 + char ip[28]; ///< 自定义的上报目标IP地址 + rm_udp_custom_config_t custom_config; ///< 自定义项内容 +} rm_realtime_push_config_t; + +/** + * @brief 四元数 + * + */ +typedef struct +{ + float w; + float x; + float y; + float z; +} rm_quat_t; + +/** + * @brief 位置坐标 + * + */ +typedef struct +{ + float x; //* unit: m + float y; + float z; +} rm_position_t; + +/** + * @brief 欧拉角 + * + */ +typedef struct +{ + float rx; //* unit: rad + float ry; + float rz; +} rm_euler_t; + +/** + * @brief 机械臂位置姿态结构体 + * @ingroup Algo + */ +typedef struct +{ + rm_position_t position; ///< 位置,单位:m + rm_quat_t quaternion; ///< 四元数 + rm_euler_t euler; ///< 欧拉角,单位:rad +}rm_pose_t; + +/** + * @brief 坐标系名称 + * 不超过10个字符 + * @ingroup ToolCoordinateConfig + * @ingroup WorkCoordinateConfig + */ +typedef struct +{ + char name[12]; +}rm_frame_name_t; + + +/** + * @brief 坐标系 + * @ingroup Algo + * @ingroup ToolCoordinateConfig + * @ingroup WorkCoordinateConfig + */ +typedef struct +{ + char frame_name[12]; ///< 坐标系名称 + rm_pose_t pose; ///< 坐标系位姿 + float payload; ///< 坐标系末端负载重量,单位:kg + float x; ///< 坐标系末端负载质心位置,单位:mm + float y; ///< 坐标系末端负载质心位置,单位:mm + float z; ///< 坐标系末端负载质心位置,单位:mm +}rm_frame_t; + +typedef struct{ + char build_time[20]; ///< 编译时间 + char version[20]; ///< 版本号 +}rm_ctrl_version_t; + +typedef struct{ + char model_version[5]; ///< 动力学模型版本号 +}rm_dynamic_version_t; + +typedef struct{ + char build_time[20]; ///<编译时间 + char version[20]; ///< 版本号 +}rm_planinfo_t; + +typedef struct { + char version[20]; ///< 算法库版本号 +}rm_algorithm_version_t; + +typedef struct { + char build_time[20]; ///<编译时间 + char version[20]; ///< 版本号 +}rm_software_build_info_t; +/** + * @brief 机械臂软件信息 + * + */ +typedef struct +{ + char product_version[20]; ///< 机械臂型号 + char robot_controller_version[10]; ///< 机械臂控制器版本,若为四代控制器,则该字段为"4.0" + rm_algorithm_version_t algorithm_info; ///< 算法库信息 + rm_software_build_info_t ctrl_info; ///< ctrl 层软件信息 + rm_dynamic_version_t dynamic_info; ///< 动力学版本(三代) + rm_software_build_info_t plan_info; ///< plan 层软件信息(三代) + rm_software_build_info_t com_info; ///< communication 模块软件信息(四代) + rm_software_build_info_t program_info; ///< 流程图编程模块软件信息(四代) +}rm_arm_software_version_t; + +/** + * @brief 错误代码结构体 + * +*/ +typedef struct +{ + uint8_t err_len; ///< 错误代码个数 + int err[24]; ///< 错误代码数组 +}rm_err_t; + +/** + * @brief 机械臂当前状态 + * +*/ +typedef struct +{ + rm_pose_t pose; ///< 机械臂当前位姿 + float joint[ARM_DOF]; ///< 机械臂当前关节角度 + rm_err_t err; +}rm_current_arm_state_t; + +/** + * @brief 机械臂关节状态参数 + * +*/ +typedef struct +{ + float joint_current[ARM_DOF]; ///< 关节电流,单位mA,精度:0.001mA + bool joint_en_flag[ARM_DOF]; ///< 当前关节使能状态 ,1为上使能,0为掉使能 + uint16_t joint_err_code[ARM_DOF]; ///< 当前关节错误码 + float joint_position[ARM_DOF]; ///< 关节角度,单位°,精度:0.001° + float joint_temperature[ARM_DOF]; ///< 当前关节温度,精度0.001℃ + float joint_voltage[ARM_DOF]; ///< 当前关节电压,精度0.001V + float joint_speed[ARM_DOF]; ///< 当前关节速度,精度0.01RPM。 +}rm_joint_status_t; + +/** + * @brief 位置示教方向 + * + */ +typedef enum +{ + RM_X_DIR_E, ///< 位置示教,x轴方向 + RM_Y_DIR_E, ///< 位置示教,y轴方向 + RM_Z_DIR_E, ///< 位置示教,z轴方向 +}rm_pos_teach_type_e; + +/** + * @brief 姿态示教方向 + * + */ +typedef enum +{ + RM_RX_ROTATE_E, ///< 姿态示教,绕x轴旋转 + RM_RY_ROTATE_E, ///< 姿态示教,绕y轴旋转 + RM_RZ_ROTATE_E, ///< 姿态示教,绕z轴旋转 +}rm_ort_teach_type_e; + +/** + * @brief 数字IO配置结构体 + * io_mode:模式,0-通用输入模式、1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、 + * 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式 + * 7-输入进入力只动位置拖动模式(六维力版本可配置)、8-输入进入力只动姿态拖动模式(六维力版本可配置) + * 9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、10-输入外部轴最大软限位复用模式(外部轴模式可配置) + * 11-输入外部轴最小软限位复用模式(外部轴模式可配置)、12-输入初始位姿功能复用模式 + * 13-输出碰撞功能复用模式、14-实时调速功能复用模式 + * io_state:数字io状态(0低 1高)(该成员在set时无效) + * io_real_time_config_t:实时调速功能,io配置 + * speed:速度取值范围0-100 (当io_mode不为14时,默认值为-1) + * mode :模式取值范围1或2 (当io_mode不为14时,默认值为-1) + * 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值 + * 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + */ +typedef struct +{ + int io_mode; // io_mode:模式0~14 + struct + { + int speed; // speed:速度取值范围0-100 + int mode; // mode :模式取值范围1或2 + }io_real_time_config_t; +}rm_io_config_t; + +/** + * @brief 数字IO状态获取结构体 + * io_state:数字io状态(0低 1高)(该成员在set时无效) + * io_config:io配置结构体 + */ +typedef struct +{ + int io_state; // io_state:数字io状态(0低 1高) + rm_io_config_t io_config; // io_config:数字io配置结构体 +}rm_io_get_t; + +/** + * @brief 复合模式拖动示教参数 + * + */ +typedef struct{ + int free_axes[6]; ///< 自由驱动方向[x,y,z,rx,ry,rz],0-在参考坐标系对应方向轴上不可拖动,1-在参考坐标系对应方向轴上可拖动 + int frame; ///< 参考坐标系,0-工作坐标系 1-工具坐标系。 + int singular_wall; ///< 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙,若无配置参数,默认启动拖动奇异墙 +}rm_multi_drag_teach_t; + +/** + * @brief 力位混合控制传感器枚举 + * + */ +typedef enum{ + RM_FP_OF_SENSOR_E = 0, ///<一维力 + RM_FP_SF_SENSOR_E, ///<六维力 +}rm_force_position_sensor_e; + +/** + * @brief 力位混合控制模式枚举 + * + */ +typedef enum{ + RM_FP_BASE_COORDINATE_E = 0, ///<基坐标系力控 + RM_FP_TOOL_COORDINATE_E, ///<工具坐标系力控 +}rm_force_position_mode_e; + +/** + * @brief 力位混合控制模式(单方向)力控方向枚举 + * + */ +typedef enum{ + RM_FP_X_E = 0, ///<沿X轴 + RM_FP_Y_E, ///<沿Y轴 + RM_FP_Z_E, ///<沿Z轴 + RM_FP_RX_E, ///<沿RX姿态方向 + RM_FP_RY_E, ///<沿RY姿态方向 + RM_FP_RZ_E, ///<沿RZ姿态方向 +}rm_force_position_dir_e; + +/** + * @brief 力位混合控制参数 + * + */ +typedef struct +{ + int sensor; ///< 传感器,0-一维力;1-六维力 + int mode; ///< 0-基坐标系力控;1-工具坐标系力控; + int control_mode[6]; ///< 6个力控方向(Fx Fy Fz Mx My Mz)的模式 0-固定模式 1-浮动模式 2-弹簧模式 3-运动模 4-力跟踪模式 8-力跟踪+姿态自适应模式 + float desired_force[6]; ///< 力控轴维持的期望力/力矩,力控轴的力控模式为力跟踪模式时,期望力/力矩设置才会生效 ,精度0.1N。 + float limit_vel[6]; ///< 力控轴的最大线速度和最大角速度限制,只对开启力控方向生效。 +}rm_force_position_t; + +/** + * @brief 透传力位混合补偿参数 + * 建议初始化方式,避免一些未知错误 + * rm_force_position_move_t my_fp_move = (rm_force_position_move_t){ 0 }; + */ +typedef struct +{ + int flag; ///< 0-下发目标角度,1-下发目标位姿 + rm_pose_t pose; ///< 当前坐标系下的目标位姿,支持四元数/欧拉角表示姿态。位置精度:0.001mm,欧拉角表示姿态,姿态精度:0.001rad,四元数方式表示姿态,姿态精度:0.000001 + float joint[ARM_DOF]; ///< 目标关节角度,单位:°,精度:0.001° + int sensor; ///< 传感器,0-一维力;1-六维力 + int mode; ///< 0-基坐标系力控;1-工具坐标系力控; + bool follow; ///< 表示驱动器的运动跟随效果,true 为高跟随,false 为低跟随。 + int control_mode[6]; ///< 6个力控方向的模式 0-固定模式 1-浮动模式 2-弹簧模式 3-运动模式 4-力跟踪模式 5-浮动+运动模式 6-弹簧+运动模式 7-力跟踪+运动模式 8-姿态自适应模式 + float desired_force[6]; ///< 力控轴维持的期望力/力矩,力控轴的力控模式为力跟踪模式时,期望力/力矩设置才会生效 ,精度0.1N。 + float limit_vel[6]; ///< 力控轴的最大线速度和最大角速度限制,只对开启力控方向生效。 + int trajectory_mode; ///< 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + int radio; ///< 曲线拟合模式0-100和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100 +}rm_force_position_move_t; + +/** + * @brief 角度透传模式结构体 + * 建议初始化方式,避免一些未知错误 + * rm_movej_canfd_mode_t my_j_canfd = (rm_movej_canfd_mode_t){ 0 }; + */ +typedef struct +{ + float* joint; // 关节角度(若为六轴机械臂,那么最后一个元素无效),单位° + float expand; // 扩展关节角度(若没有扩展关节,那么此成员值无效) + bool follow; // 跟随模式,0-低跟随,1-高跟随,若使用高跟随,透传周期要求不超过 10ms + int trajectory_mode; // 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + int radio; // 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100 +}rm_movej_canfd_mode_t; + +/** + * @brief 姿态透传模式结构体 + * 建议初始化方式,避免一些未知错误 + * rm_movep_canfd_mode_t my_p_canfd = (rm_movep_canfd_mode_t){ 0 }; + */ +typedef struct +{ + rm_pose_t pose; // 位姿 (优先采用四元数表达) + bool follow; // 跟随模式,0-低跟随,1-高跟随,若使用高跟随,透传周期要求不超过 10ms + int trajectory_mode; // 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + int radio; // 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~1000,曲线拟合模式下取值范围0~100 +}rm_movep_canfd_mode_t; + +/** + * @brief 无线网络信息结构体 + * + */ +typedef struct{ + int channel; ///< 如果是 AP 模式,则存在此字段,标识 wifi 热点的物理信道号 + char ip[16]; ///< IP 地址 + char mac[18]; ///< MAC 地址 + char mask[16]; ///< 子网掩码 + char mode[5]; ///< ap 代表热点模式,sta 代表联网模式,off 代表未开启无线模式 + char password[16]; ///< 密码 + char ssid[32]; ///< 网络名称 (SSID) +}rm_wifi_net_t; + +/** + * @brief 机械臂所有状态参数 + * +*/ +typedef struct +{ + float joint_current[ARM_DOF]; ///< 关节电流,单位mA + int joint_en_flag[ARM_DOF]; ///< 关节使能状态 + float joint_temperature[ARM_DOF]; ///< 关节温度,单位℃ + float joint_voltage[ARM_DOF]; ///< 关节电压,单位V + int joint_err_code[ARM_DOF]; ///< 关节错误码 + rm_err_t err; ///< 错误代码 +}rm_arm_all_state_t; + +/** + * @brief 夹爪状态 + * + */ +typedef struct +{ + int enable_state; ///< 夹爪使能标志,0 表示未使能,1 表示使能 + int status; ///< 夹爪在线状态,0 表示离线, 1表示在线 + int error; ///< 夹爪错误信息,低8位表示夹爪内部的错误信息bit5-7 保留bit4 内部通bit3 驱动器bit2 过流 bit1 过温bit0 堵转 + int mode; ///< 当前工作状态:1 夹爪张开到最大且空闲,2 夹爪闭合到最小且空闲,3 夹爪停止且空闲,4 夹爪正在闭合,5 夹爪正在张开,6 夹爪闭合过程中遇到力控停止 + int current_force; ///< 夹爪当前的压力,单位g + int temperature; ///< 当前温度,单位℃ + int actpos; ///< 夹爪开口度 +}rm_gripper_state_t; + +/** + * @brief 六维力传感器数据结构体 + * +*/ +typedef struct { + float force_data[6]; ///< 当前力传感器原始数据,力的单位为N;力矩单位为Nm。 + float zero_force_data[6]; ///< 当前力传感器系统外受力数据,力的单位为N;力矩单位为Nm。 + float work_zero_force_data[6]; ///< 当前工作坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。 + float tool_zero_force_data[6]; ///< 当前工具坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。 +} rm_force_data_t; + +/** + * @brief 一维力传感器数据结构体 + * +*/ +typedef struct { + float Fz; ///< 原始数据 + float zero_Fz; ///< 传感器坐标系下系统外受力数据,力的单位为N;力矩单位为Nm。 + float work_zero_Fz; ///< 当前工作坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。 + float tool_zero_Fz; ///< 当前工具坐标系下系统外受力原始数据,力的单位为N;力矩单位为Nm。 +} rm_fz_data_t; + +/** + * @brief 外设数据读写参数结构体 + * +*/ +typedef struct { + int port; ///< 通讯端口,0-控制器RS485端口,1-末端接口板RS485接口,3-控制器ModbusTCP设备 + int address; ///< 数据起始地址 + int device; ///< 外设设备地址 + int num; ///< 要读的数据的数量 +} rm_peripheral_read_write_params_t; + +/** + * @brief 升降机构、扩展关节状态结构体 + * +*/ +typedef struct { + int pos; ///< 扩展关节角度,单位度,精度 0.001°(若为升降机构高度,则单位:mm,精度:1mm,范围:0 ~2300) + int current; ///< 驱动电流,单位:mA,精度:1mA + int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码 + int mode; ///< 当前状态,0-空闲,1-正方向速度运动,2-正方向位置运动,3-负方向速度运动,4-负方向位置运动 +} rm_expand_state_t; + +/** + * @brief 文件下发 + * @ingroup OnlineProgramming + */ +typedef struct { + char project_path[300]; ///< 下发文件路径文件名 + int project_path_len; ///< 名称长度 + int plan_speed; ///< 规划速度比例系数 + int only_save; ///< 0-保存并运行文件,1-仅保存文件,不运行 + int save_id; ///< 保存到控制器中的编号 + int step_flag; ///< 设置单步运行方式模式,1-设置单步模式 0-设置正常运动模式 + int auto_start; ///< 设置默认在线编程文件,1-设置默认 0-设置非默认 + int project_type; ///< 下发文件类型。0-在线编程文件,1-拖动示教轨迹文件 + // int err_line; ///< 若运行失败,该参数返回有问题的工程行数,err_line 为 0,则代表校验数据长度不对 +} rm_send_project_t; + +/** + * @brief 在线编程存储信息 + * @ingroup OnlineProgramming + */ +typedef struct { + int id; ///< 在线编程文件id + int size; ///< 文件大小 + int speed; ///< 默认运行速度 + char trajectory_name[32]; ///< 文件名称 +}rm_trajectory_data_t; +/** + * @brief 查询在线编程列表 + * @ingroup OnlineProgramming + */ +typedef struct +{ + int page_num; // 页码 + int page_size; // 每页大小 + int list_size; //返回总数量 + char vague_search[32]; // 模糊搜索 + rm_trajectory_data_t trajectory_list[100]; // 符合的在线编程列表 +}rm_program_trajectorys_t; + +/** + * @brief 在线编程运行状态 + * @ingroup OnlineProgramming + */ +typedef struct +{ + int run_state; ///< 运行状态 0 未开始 1运行中 2暂停中 + int id; ///< 运行轨迹编号 + int edit_id; ///< 上次编辑的在线编程编号 id + int plan_num; ///< 运行行数 + int total_loop; ///< 循环指令数量 + int step_mode; ///< 单步模式,1 为单步模式,0 为非单步模式 + int plan_speed; ///< 全局规划速度比例 1-100 + int loop_num[100]; ///< 循环行数 + int loop_cont[100]; ///< 对应循环次数 +}rm_program_run_state_t; + +/** + * @brief 流程图程序运行状态 + */ +typedef struct +{ + int run_state; ///< 运行状态 0 未开始 1运行中 2暂停中 + int id; ///< 当前使能的文件id。 + char name[32]; ///< 当前使能的文件名称。 + int plan_speed; ///< 当前使能的文件全局规划速度比例 1-100。 + int step_mode; ///< 单步模式,0为空,1为正常, 2为单步。 + char modal_id[50]; ///< 运行到的流程图块的id。未运行则不返回 +}rm_flowchart_run_state_t; + +/** + * @brief 全局路点存储信息 + * @ingroup OnlineProgramming + */ +typedef struct +{ + char point_name[20]; ///< 路点名称 + float joint[ARM_DOF]; ///< 关节角度 + rm_pose_t pose; ///< 位姿信息 + char work_frame[12]; ///< 工作坐标系名称 + char tool_frame[12]; ///< 工具坐标系名称 + char time[50]; ///< 路点新增或修改时间 +}rm_waypoint_t; +/** + * @brief 全局路点列表 + * @ingroup OnlineProgramming + */ +typedef struct{ + int page_num; ///< 页码 + int page_size; ///< 每页大小 + int total_size; ///< 列表长度 + char vague_search[32]; ///< 模糊搜索 + int list_len; ///<返回符合的全局路点列表长度 + rm_waypoint_t points_list[100]; ///< 返回符合的全局路点列表 +}rm_waypoint_list_t; + +/** + * @brief 几何模型长方体参数 + * @ingroup Electronic_Fence + */ +typedef struct{ + float x_min_limit; ///< 长方体基于世界坐标系 X 方向最小位置,单位 m + float x_max_limit; ///< 长方体基于世界坐标系 X 方向最大位置,单位 m + float y_min_limit; ///< 长方体基于世界坐标系 Y 方向最小位置,单位 m + float y_max_limit; ///< 长方体基于世界坐标系 Y 方向最大位置,单位 m + float z_min_limit; ///< 长方体基于世界坐标系 Z 方向最小位置,单位 m + float z_max_limit; ///< 长方体基于世界坐标系 Z 方向最大位置,单位 m +}rm_fence_config_cube_t; +/** + * @brief 几何模型点面矢量平面参数 + * @ingroup Electronic_Fence + */ +typedef struct{ + float x1, y1, z1; ///< 点面矢量平面三点法中的第一个点坐标,单位 m + float x2, y2, z2; ///< 点面矢量平面三点法中的第二个点坐标,单位 m + float x3, y3, z3; ///< 点面矢量平面三点法中的第三个点坐标,单位 m +}rm_fence_config_plane_t; +/** + * @brief 几何模型球体参数 + * @ingroup Electronic_Fence + */ +typedef struct{ + float x; ///< 表示球心在世界坐标系 X 轴的坐标,单位 m + float y; ///< 表示球心在世界坐标系 Y 轴的坐标,单位 m + float z; ///< 表示球心在世界坐标系 Z 轴的坐标,单位 m + float radius; ///< 表示半径,单位 m +}rm_fence_config_sphere_t; +/** + * @brief 几何模型参数 + * @ingroup Electronic_Fence + */ +typedef struct{ + int form; ///< 形状,1 表示长方体,2 表示点面矢量平面,3 表示球体 + char name[12]; ///< 电子围栏名称,不超过 10 个字节,支持字母、数字、下划线 + rm_fence_config_cube_t cube; ///< 长方体参数 + rm_fence_config_plane_t plan; ///< 点面矢量平面参数 + rm_fence_config_sphere_t sphere; ///< 球体参数 +}rm_fence_config_t; + +/** + * @brief 几何模型名称结构体 + * @ingroup Electronic_Fence + */ +typedef struct +{ + char name[12]; ///< 几何模型名称,不超过10个字符 +}rm_fence_names_t; + +/** + * @brief 几何模型参数列表 + * @ingroup Electronic_Fence + */ +typedef struct +{ + rm_fence_config_t config[10]; +}rm_fence_config_list_t; +/** + * @brief 包络球参数 + * + */ +typedef struct{ + char name[12]; ///< 工具包络球体的名称,1-10 个字节,支持字母数字下划线 + float radius; ///< 工具包络球体的半径,单位 m + float x; ///< 工具包络球体球心基于末端法兰坐标系的 X 轴坐标,单位 m + float y; ///< 工具包络球体球心基于末端法兰坐标系的 Y 轴坐标,单位 m + float z; ///< 工具包络球体球心基于末端法兰坐标系的 Z 轴坐标,单位 m +}rm_envelopes_ball_t; +/** + * @brief 包络球参数集合 + * + */ +typedef struct{ + rm_envelopes_ball_t balls[5];///< 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + int size; ///< 包络球数量 + char tool_name[12];///< 控制器中已存在的工具坐标系名称,如果不存在该字段,则为临时设置当前包络参数 +}rm_envelope_balls_list_t; + +/** + * @brief 电子围栏/虚拟墙使能状态参数 + * + */ +typedef struct +{ + bool enable_state; ///< 电子围栏/虚拟墙使能状态,true 代表使能,false 代表禁使能 + int in_out_side; ///< 0-机器人在电子围栏/虚拟墙内部,1-机器人在电子围栏外部 + int effective_region; ///< 0-电子围栏针对整臂区域生效,1-虚拟墙针对末端生效 +}rm_electronic_fence_enable_t; + + +/** + * @brief (UDP主动上报机械臂信息)力传感器数据结构体 + * +*/ +typedef struct { + float force[6]; ///< 当前力传感器原始数据,0.001N或0.001Nm + float zero_force[6]; ///< 当前力传感器系统外受力数据,0.001N或0.001Nm + int coordinate; ///< 系统外受力数据的坐标系,0为传感器坐标系 1为当前工作坐标系 2为当前工具坐标系 +} rm_force_sensor_t; + +/*** + * 扩展关节数据 + * + */ +typedef struct { + float pos; ///< 当前角度 精度 0.001°,单位:° + int current; ///< 当前驱动电流,单位:mA,精度:1mA + int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码 + int en_flag; ///< 当前关节使能状态 ,1 为上使能,0 为掉使能 + int joint_id; ///< 关节id号 + int mode; ///< 当前升降状态,0-空闲,1-正方向速度运动,2-正方向位置运动,3-负方向速度运动,4-负方向位置运动 +} rm_udp_expand_state_t; + +/*** + * 升降机构状态 + * + */ +typedef struct { + int height; ///< 当前升降机构高度,单位:mm,精度:1mm + float pos; ///< 当前角度 精度 0.001°,单位:° + int current; ///< 当前驱动电流,单位:mA,精度:1mA + int err_flag; ///< 驱动错误代码,错误代码类型参考关节错误代码 + int en_flag; ///< 当前关节使能状态 ,1 为上使能,0 为掉使能 +} rm_udp_lift_state_t; +/*** + * 灵巧手状态 + * + */ +typedef struct { + int hand_pos[6]; ///< 表示灵巧手位置 + int hand_angle[6]; ///< 表示灵巧手角度 + int hand_force[6]; ///< 表示灵巧手自由度力,单位mN + int hand_state[6]; ///< 表示灵巧手自由度状态,由灵巧手厂商定义状态含义 + int hand_err; ///< 表示灵巧手系统错误,由灵巧手厂商定义错误含义,例如因时状态码如下:1表示有错误,0表示无错误 +} rm_udp_hand_state_t; + +/*** + * + * 轨迹连接配置 + */ +typedef enum{ + RM_TRAJECTORY_DISCONNECT_E = 0, ///<立即规划并执行轨迹,不连接后续轨迹 + RM_TRAJECTORY_CONNECT_E ///<将当前轨迹与下一条轨迹一起规划 +}rm_trajectory_connect_config_e; + +/** + * @brief 机械臂当前状态 + * + */ +typedef enum { + RM_IDLE_E, // 使能但空闲状态 + RM_MOVE_L_E, // move L运动中状态 + RM_MOVE_J_E, // move J运动中状态 + RM_MOVE_C_E, // move C运动中状态 + RM_MOVE_S_E, // move S运动中状态 + RM_MOVE_THROUGH_JOINT_E, // 角度透传状态 + RM_MOVE_THROUGH_POSE_E, // 位姿透传状态 + RM_MOVE_THROUGH_FORCE_POSE_E, // 力控透传状态 + RM_MOVE_THROUGH_CURRENT_E, // 电流环透传状态 + RM_STOP_E, // 急停状态 + RM_SLOW_STOP_E, // 缓停状态 + RM_PAUSE_E, // 暂停状态 + RM_CURRENT_DRAG_E, // 电流环拖动状态 + RM_SENSOR_DRAG_E, // 六维力拖动状态 + RM_TECH_DEMONSTRATION_E // 示教状态 +} rm_udp_arm_current_status_e; + +/*** + * aloha主臂状态 + * + */ +typedef struct { + int io1_state; ///< IO1状态(手柄光电检测),0为按键未触发,1为按键触发。 + int io2_state; ///< IO2状态(手柄光电检测),0为按键未触发,1为按键触发。 +} rm_udp_aloha_state_t; + +/** + * 末端设备基础信息(末端生态协议支持) +*/ +typedef struct{ + char manu[10]; // 设备厂家 + int type; // 设备类型 1:两指夹爪 2:五指灵巧手 3:三指夹爪 + char hv[10]; // 硬件版本 + char sv[10]; // 软件版本 + char bv[10]; // boot版本 + int id; // 设备ID + int dof; // 自由度 + int check; // 自检开关 + int bee; // 蜂鸣器开关 + bool force; // 力控支持 + bool touch; // 触觉支持 + int touch_num; // 触觉个数 + int touch_sw; // 触觉开关 + int hand; // 手方向 1 :左手 2: 右手 + int pos_up[12]; // 位置上限,单位:无量纲 + int pos_low[12]; // 位置下限,单位:无量纲 + int angle_up[12]; // 角度上限,单位:0.01度 + int angle_low[12]; // 角度下限,单位:0.01度 + int speed_up[12]; // 速度上限,单位:无量纲 + int speed_low[12]; // 速度下限,单位:无量纲 + int force_up[12]; // 力上限,单位:0.001N + int force_low[12]; // 力下限,单位:0.001N +} rm_plus_base_info_t; +// 单位:无量纲 +/** + * 末端设备实时信息(末端生态协议支持) +*/ +typedef struct{ + int sys_state; // 系统状态:0正常1设备故障 + int dof_state[12]; // 各自由度当前状态:0正在松开1正在闭合2位置到位停止3力控到位停止4触觉到位停止5电流保护停止6发生故障 + int dof_err[12]; // 各自由度错误信息 + int pos[12]; // 各自由度当前位置,单位:无量纲 + int speed[12]; //各自由度当前速度,闭合正,松开负,单位:无量纲 + int angle[12]; // 各自由度当前角度,单位:0.01度 + int current[12]; // 各自由度当前电流,单位:mA + int normal_force[18]; // 自由度触觉三维力的法向力,1-6自由度触觉三维力的法向力*3 + int tangential_force[18]; // 自由度触觉三维力的切向力 + int tangential_force_dir[18]; // 自由度触觉三维力的切向力方向 + uint32_t tsa[12]; // 自由度触觉自接近 + uint32_t tma[12]; // 自由度触觉互接近 + int touch_data[18]; // 触觉传感器原始数据(示例中有,但未显示数据的JSON情况) + int force[12]; //自由度力矩,闭合正,松开负,单位0.001N +} rm_plus_state_info_t; + + +/** + * @brief udp主动上报机械臂信息 + * +*/ +typedef struct +{ + int errCode; ///< 数据解析错误码,-3为数据解析错误,代表推送的数据不完整或格式不正确 + char arm_ip[16]; ///< 推送数据的机械臂的IP地址 + rm_joint_status_t joint_status; ///< 关节状态 + rm_force_sensor_t force_sensor; ///< 力数据(六维力或一维力版本支持) + rm_err_t err; ///< 错误码 + rm_pose_t waypoint; ///< 当前路点信息 + rm_udp_lift_state_t liftState; ///< 升降关节数据 + rm_udp_expand_state_t expandState; ///< 扩展关节数据 + rm_udp_hand_state_t handState; ///< 灵巧手数据 + rm_udp_arm_current_status_e arm_current_status; ///< 机械臂状态 + rm_udp_aloha_state_t aloha_state; ///< aloha主臂状态 + int rm_plus_state; ///< 末端设备状态,0-设备在线,1-表示协议未开启,2-表示协议开启但是设备不在线 + rm_plus_base_info_t plus_base_info; ///< 末端设备基础信息 + rm_plus_state_info_t plus_state_info; ///< 末端设备实时信息 +}rm_realtime_arm_joint_state_t; + +/** + * @brief 逆解参数 + * @ingroup Algo + */ +typedef struct { + float q_in[ARM_DOF]; ///< 上一时刻关节角度,单位° + rm_pose_t q_pose; ///< 目标位姿 + uint8_t flag; ///< 姿态参数类别:0-四元数;1-欧拉角 +} rm_inverse_kinematics_params_t; + +typedef struct { + int result; // 0:成功,1:逆解失败,-1:上一时刻关节角度输入为空或超关节限位,-2:目标位姿四元数不合法, -3:当前机器人非六自由度,当前仅支持六自由度机器人 + int num; // number of solutions + float q_ref[8]; // 参考关节角度,通常是当前关节角度, 单位 ° + float q_solve[8][8]; // 关节角全解, 单位 ° +} rm_inverse_kinematics_all_solve_t; + +/** + * @brief 包络球描述数据结构 +*/ +typedef struct +{ + float radius; // 球体半径(单位:m) + float centrePoint[3]; // 球体中心位置(单位:m,以法兰坐标系为参考坐标系) +} rm_tool_sphere_t; // 工具包络球参数 + + +/** + * @brief 旋转矩阵 + * @ingroup Algo + */ +typedef struct +{ + short irow; + short iline; + float data[4][4]; +} rm_matrix_t; +/** + * @brief 机械臂事件回调函数 + * @ingroup Init_Class + */ +typedef void (*rm_event_callback_ptr)(rm_event_push_data_t data); +/** + * @brief UDP机械臂状态主动上报回调函数 + * @ingroup Init_Class + */ +typedef void (*rm_realtime_arm_state_callback_ptr)(rm_realtime_arm_joint_state_t data); + +/** + * @brief 机械臂基本信息 + * @ingroup Init_Class + */ +typedef struct +{ + uint8_t arm_dof; ///< 机械臂自由度 + rm_robot_arm_model_e arm_model; ///< 机械臂型号 + rm_force_type_e force_type; ///< 末端力传感器版本 + uint8_t robot_controller_version; ///< 机械臂控制器版本,4:四代控制器,3:三代控制器。 +}rm_robot_info_t; + +/** + * @brief 机械臂控制句柄 + * @ingroup Init_Class + */ +typedef struct { + int id; ///< 句柄id,连接成功id大于0,连接失败返回-1 +}rm_robot_handle; + + +typedef struct +{ + float d[8]; //* unit: m + float a[8]; //* unit: m + float alpha[8]; //* unit: ° + float offset[8]; //* unit: ° +} rm_dh_t; + +/** + * @brief 版本号结构体 + * 不超过10个字符 + * @ingroup ToolCoordinateConfig + * @ingroup WorkCoordinateConfig + */ +typedef struct { + char version[10]; +} rm_version_t; + +/** + * @brief 轨迹信息结构体 + */ +typedef struct { + int point_num; ///< 轨迹点数量 + char name[20]; ///< 轨迹名称 + char create_time[20]; ///< 创建时间 +}rm_trajectory_info_t; +/** + * @brief 轨迹列表结构体 + * @ingroup OnlineProgramming + */ +typedef struct{ + int page_num; ///< 页码 + int page_size; ///< 每页大小 + int total_size; ///< 列表长度 + char vague_search[32]; ///< 模糊搜索 + int list_len; ///<返回符合的轨迹列表长度 + rm_trajectory_info_t tra_list[100]; ///< 返回符合的轨迹列表 +}rm_trajectory_list_t; +/** + * @brief Modbus TCP主站信息结构体 + */ +typedef struct { + char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符 + char ip[16]; // TCP主站 IP 地址 + int port; // TCP主站端口号 +}rm_modbus_tcp_master_info_t; +/** + * @brief Modbus TCP主站列表结构体 + */ +typedef struct{ + int page_num; ///< 页码 + int page_size; ///< 每页大小 + int total_size; ///< 列表长度 + char vague_search[32]; ///< 模糊搜索 + int list_len; ///<返回符合的TCP主站列表长度 + rm_modbus_tcp_master_info_t master_list[100]; ///< 返回符合的TCP主站列表 +}rm_modbus_tcp_master_list_t; + +/** + * @brief Modbus RTU读数据参数结构体 + */ +typedef struct { + int address; ///< 数据起始地址 + int device; ///< 外设设备地址 + int type; ///< 0-控制器端modbus主机;1-工具端modbus主机。 + int num; ///< 要读的数据的数量,数据长度不超过109 +}rm_modbus_rtu_read_params_t; +/** + * @brief Modbus RTU写数据结构体 + */ +typedef struct { + int address; ///< 数据起始地址 + int device; ///< 外设设备地址 + int type; ///< 0-控制器端modbus主机;1-工具端modbus主机。 + int num; ///< 要写的数据的数量,最大不超过100 + int data[120]; ///< 要写的数据,数据长度不超过100 +}rm_modbus_rtu_write_params_t; + +/** + * @brief Modbus TCP读数据参数结构体 + */ +typedef struct { + int address; // 数据起始地址 + char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port) + char ip[16]; // 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port) + int port; // 主机连接的端口号 + int num; // 读取数据数量,最大不超过100 +}rm_modbus_tcp_read_params_t; +/** + * @brief Modbus TCP写数据结构体 + */ +typedef struct { + int address; // 数据起始地址 + char master_name[20]; // Modbus 主站名称,最大长度15个字符,不超过15个字符(master_name与IP二选一,若有IP和port优先使用IP和port) + char ip[16]; // 主机连接的 IP 地址(master_name与IP二选一,若有IP和port优先使用IP和port) + int port; // 主机连接的端口号 + int num; // 写入数据数量,最大不超过100 + int data[120]; // 写入的数据,数据长度不超过100 +}rm_modbus_tcp_write_params_t; + +#ifdef __cplusplus +} +#endif + +#endif \ No newline at end of file diff --git a/include/rm_interface.h b/include/rm_interface.h new file mode 100644 index 0000000..582e164 --- /dev/null +++ b/include/rm_interface.h @@ -0,0 +1,4533 @@ +/** + * @file rm_interface.h + * @brief 该文档声明了机械臂所有操作接口 + * @author aisha + * @version 0.1.0 + * @date 2024.4.20 + * @copyright 睿尔曼智能科技有限公司 + */ + +#ifndef RM_FUNCTION_H +#define RM_FUNCTION_H + +#include "rm_define.h" +#include "rm_interface_global.h" +#include "rm_version.h" +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * @defgroup Init_Class 连接机械臂 + * + * 此模块为API及机械臂初始化相关接口,包含API版本号查询、API初始化、连接/断开机械臂、日志设置、 + * 机械臂仿真/真实模式设置、机械臂信息获取、运动到位信息及机械臂实时状态信息回调函数注册等 + * @{ + */ +/** + * @brief 查询sdk版本号 + * @return char* 返回版本号 + * @code + * char *version = rm_api_version(); + * printf("api version: %s\n", version); + * @endcode + */ +RM_INTERFACE_EXPORT char* rm_api_version(void); +/** + * @brief 初始化线程模式 + * + * @param mode RM_SINGLE_MODE_E:单线程模式,单线程非阻塞等待数据返回; + * RM_DUAL_MODE_E:双线程模式,增加接收线程监测队列中的数据; + * RM_TRIPLE_MODE_E:三线程模式,在双线程模式基础上增加线程监测UDP接口数据; + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 创建线程失败。查看日志以获取具体错误 + */ +RM_INTERFACE_EXPORT int rm_init(rm_thread_mode_e mode); + +/** + * @brief 关闭所有连接,销毁所有线程 + * + * @return int 函数执行的状态码。 + - 0: 成功。 + */ +RM_INTERFACE_EXPORT int rm_destroy(void); + +/** + * @brief 日志打印配置 + * + * @param LogCallback 日志打印回调函数 + * @param level 日志打印等级,0:debug级别,1:info级别,2:warn:级别,3:error级别 + */ +RM_INTERFACE_EXPORT void rm_set_log_call_back(void (*LogCallback)(const char* message, va_list args),int level); + +/** + * @brief 保存日志到文件 + * + * @param path 日志保存文件路径 + */ +RM_INTERFACE_EXPORT void rm_set_log_save(const char* path); + +/** + * @brief 设置全局超时时间 + * + * @param timeout 接收控制器返回指令超时时间,多数接口默认超时时间为500ms,单位ms + */ +RM_INTERFACE_EXPORT void rm_set_timeout(int timeout); + +/** + * @brief 创建一个机械臂,用于实现对该机械臂的控制 + * + * @param ip 机械臂的ip地址 + * @param port 机械臂的端口号 + * @return rm_robot_handle* 创建成功后,返回机械臂控制句柄,连接成功句柄id大于0,连接失败句柄id返回-1,达到最大连接数5创建失败返回空 + */ +RM_INTERFACE_EXPORT rm_robot_handle *rm_create_robot_arm(const char *ip,int port); + +/** + * @brief 根据句柄删除机械臂 + * + * @param handle 需要删除的机械臂句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + */ +RM_INTERFACE_EXPORT int rm_delete_robot_arm(rm_robot_handle *handle); +/** + * @brief 机械臂仿真/真实模式设置 + * + * @param handle 机械臂控制句柄 + * @param mode 模式 0:仿真模式 1:真实模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_run_mode(rm_robot_handle *handle, int mode); +/** + * @brief 机械臂仿真/真实模式获取 + * + * @param handle 机械臂控制句柄 + * @param mode 模式 0:仿真模式 1:真实模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_run_mode(rm_robot_handle *handle,int *mode); +/** + * @brief 获取机械臂基本信息 + * + * @param handle 机械臂控制句柄 + * @param robot_info 存放机械臂基本信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + - -2: 获取到的机械臂基本信息非法,检查句柄是否已被删除。 + */ +RM_INTERFACE_EXPORT int rm_get_robot_info(rm_robot_handle *handle, rm_robot_info_t *robot_info); +/** + * @brief 机械臂事件回调函数注册 + * @details 当机械臂返回运动到位指令或者文件运行结束指令时会有数据返回 + * @attention 单线程无法使用该函数获取到位信息 + * @param handle 机械臂控制句柄 + * @param event_callback 机械臂事件回调函数,该回调函数接收rm_event_push_data_t类型的数据作为参数,没有返回值。 + */ +RM_INTERFACE_EXPORT void rm_get_arm_event_call_back(rm_event_callback_ptr event_callback); +/** + * @brief UDP机械臂状态主动上报信息回调注册 + * + * @param handle 机械臂控制句柄 + * @param realtime_callback 机械臂状态信息回调函数 + */ +RM_INTERFACE_EXPORT void rm_realtime_arm_state_call_back(rm_realtime_arm_state_callback_ptr realtime_callback); +/** @} */ // 结束初始化组的定义 +/** + * @defgroup Joint_Config 关节配置 + * + * 对机械臂的关节参数进行设置,如果关节发生错误,则无法修改关节参数,必须先清除关节错误代码。另外设置关节之前, + * 必须先将关节掉使能,否则会设置不成功。 + * 关节所有参数在修改完成后,会自动保存到关节 Flash,立即生效,之后关节处于掉使能状态,修改完参数后必须 + * 发送指令控制关节上使能。 + * @attention 睿尔曼机械臂在出厂前所有参数都已经配置到最佳状态,一般不建议用户修改关节的底层参数。若用户确需修改,首先 + * 应使机械臂处于非使能状态,然后再发送修改参数指令,参数设置成功后,发送关节恢复使能指令。需要注意的是,关节恢复 + * 使能时,用户需要保证关节处于静止状态,以免上使能过程中关节发生报错。关节正常上使能后,用户方可控制关节运动。 + * @{ + */ +/** + * @brief 设置关节最大速度 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_speed 关节最大速度,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_speed(rm_robot_handle *handle,int joint_num,float max_speed); +/** + * @brief 设置关节最大加速度 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_acc 关节最大加速度,单位:°/s² + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_acc(rm_robot_handle *handle,int joint_num,float max_acc); +/** + * @brief 设置关节最小限位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param min_pos 关节最小位置,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_min_pos(rm_robot_handle *handle,int joint_num,float min_pos); +/** + * @brief 设置关节最大限位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_pos 关节最大位置,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_pos(rm_robot_handle *handle,int joint_num,float max_pos); +/** + * @brief 设置关节最大速度(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_speed 关节最大速度,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_speed(rm_robot_handle *handle,int joint_num,float max_speed); +/** + * @brief 设置关节最大加速度(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_acc 关节最大加速度,单位:°/s² + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_acc(rm_robot_handle *handle,int joint_num,float max_acc); +/** + * @brief 设置关节最小限位(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param min_pos 关节最小位置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_min_pos(rm_robot_handle *handle,int joint_num,float min_pos); +/** + * @brief 设置关节最大限位(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_pos 关节最大位置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_pos(rm_robot_handle *handle,int joint_num,float max_pos); +/** + * @brief 设置关节使能状态 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param en_state 1:上使能 0:掉使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_en_state(rm_robot_handle *handle,int joint_num,int en_state); +/** + * @brief 设置关节零位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_zero_pos(rm_robot_handle *handle,int joint_num); +/** + * @brief 清除关节错误代码 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_clear_err(rm_robot_handle *handle,int joint_num); +/** + * @brief 一键设置关节限位 + * + * @param handle 机械臂句柄 + * @param limit_mode 1-正式模式,各关节限位为规格参数中的软限位和硬件限位 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_auto_set_joint_limit(rm_robot_handle *handle,int limit_mode); +/** + * @brief 查询关节最大速度 + * + * @param handle 机械臂句柄 + * @param max_speed 关节1~7转速数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_speed(rm_robot_handle *handle,float *max_speed); +/** + * @brief 查询关节最大加速度 + * + * @param handle 机械臂句柄 + * @param max_acc 关节1~7加速度数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_acc(rm_robot_handle *handle,float *max_acc); +/** + * @brief 查询关节最小限位 + * + * @param handle 机械臂句柄 + * @param min_pos 关节1~7最小位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_min_pos(rm_robot_handle *handle,float *min_pos); +/** + * @brief 查询关节最大限位 + * + * @param handle 机械臂句柄 + * @param max_pos 关节1~7最大位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_pos(rm_robot_handle *handle,float *max_pos); +/** + * @brief 查询关节(驱动器)最大速度 + * + * @param handle 机械臂句柄 + * @param max_speed 关节1~7转速数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_speed(rm_robot_handle *handle,float *max_speed); +/** + * @brief 查询关节(驱动器)最大加速度 + * + * @param handle 机械臂句柄 + * @param max_acc 关节1~7加速度数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_acc(rm_robot_handle *handle,float *max_acc); +/** + * @brief 查询关节(驱动器)最小限位 + * + * @param handle 机械臂句柄 + * @param min_pos 关节1~7最小位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_min_pos(rm_robot_handle *handle,float *min_pos); +/** + * @brief 查询关节(驱动器)最大限位 + * + * @param handle 机械臂句柄 + * @param max_pos 关节1~7最大位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_pos(rm_robot_handle *handle,float *max_pos); +/** + * @brief 查询关节使能状态 + * + * @param handle 机械臂句柄 + * @param en_state 关节1~7使能状态数组,1-使能状态,0-掉使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_en_state(rm_robot_handle *handle,uint8_t *en_state); +/** + * @brief 查询关节错误代码 + * + * @param handle 机械臂句柄 + * @param err_flag 反馈关节错误代码,错误码请参见 \ref robotic_error + * @param brake_state 反馈关节抱闸状态,1 代表抱闸未打开,0 代表抱闸已打开 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_err_flag(rm_robot_handle *handle,uint16_t *err_flag,uint16_t *brake_state); +/** @} */ // 结束关节配置组的定义 + +/** + * @defgroup ArmTipVelocityParameters 机械臂末端参数配置 + * + * 机械臂末端运动参数设置及获取 + * @{ + */ +/** + * @brief 设置机械臂末端最大线速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大线速度,单位m/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_line_speed(rm_robot_handle *handle,float speed); +/** + * @brief 设置机械臂末端最大线加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大线加速度,单位m/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_line_acc(rm_robot_handle *handle,float acc); +/** + * @brief 设置机械臂末端最大角速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大角速度,单位rad/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_angular_speed(rm_robot_handle *handle,float speed); +/** + * @brief 设置机械臂末端最大角加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大角加速度,单位rad/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_angular_acc(rm_robot_handle *handle,float acc); +/** + * @brief 设置机械臂末端参数为默认值 + * + * @param handle 机械臂句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_tcp_init(rm_robot_handle *handle); +/** + * @brief 设置机械臂动力学碰撞检测等级 + * + * @param handle 机械臂句柄 + * @param collision_stage 存放碰撞等级值,数据为0-8,0-无碰撞检测,8-碰撞检测最灵敏 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_collision_state(rm_robot_handle *handle,int collision_stage); +/** + * @brief 查询碰撞防护等级 + * + * @param handle 机械臂句柄 + * @param collision_stage 等级,范围:0~8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_collision_stage(rm_robot_handle *handle,int *collision_stage); +/** + * @brief 获取机械臂末端最大线速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大线速度,单位m/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_line_speed(rm_robot_handle *handle, float *speed); +/** + * @brief 获取机械臂末端最大线加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大线加速度,单位m/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_line_acc(rm_robot_handle *handle, float *acc); +/** + * @brief 获取机械臂末端最大角速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大角速度,单位rad/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_angular_speed(rm_robot_handle *handle, float *speed); +/** + * @brief 获取机械臂末端最大角加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大角加速度,单位rad/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_angular_acc(rm_robot_handle *handle, float *acc); +/** + * @brief 设置DH参数 + * + * @param handle 机械臂控制句柄 + * @param dh DH参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DH_data(rm_robot_handle *handle, rm_dh_t dh); +/** + * @brief 获取DH参数 + * + * @param handle 机械臂控制句柄 + * @param dh DH参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_DH_data(rm_robot_handle *handle, rm_dh_t *dh); +/** + * @brief 恢复机械臂默认 DH 参数 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DH_data_default(rm_robot_handle *handle); +/** @} */ // 结束组的定义 +/** + * @defgroup ToolCoordinateConfig 工具坐标系配置 + * + * 工具坐标系标定、切换、删除、修改、查询及工具包络参数等管理 + * @{ + */ +/** + * @brief 六点法自动设置工具坐标系 标记点位 + * + * @param handle 机械臂控制句柄 + * @param point_num 1~6代表6个标定点 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_auto_tool_frame(rm_robot_handle *handle,int point_num); +/** + * @brief 六点法自动设置工具坐标系 提交 + * + * @param handle 机械臂控制句柄 + * @param name 工具坐标系名称,不能超过十个字节。 + * @param payload 新工具执行末端负载重量 单位kg + * @param x 新工具执行末端负载位置 位置x 单位m + * @param y 新工具执行末端负载位置 位置y 单位m + * @param z 新工具执行末端负载位置 位置z 单位m + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_generate_auto_tool_frame(rm_robot_handle *handle, const char *name,float payload,float x,float y,float z); +/** + * @brief 手动设置工具坐标系 + * + * @param handle 机械臂句柄 + * @param frame 新工具坐标系参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 可能情况:要设置的坐标系名称已存在 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_manual_tool_frame(rm_robot_handle *handle, rm_frame_t frame); +/** + * @brief 切换当前工具坐标系 + * + * @param handle 机械臂句柄 + * @param tool_name 目标工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。可能情况:切换的坐标系不存在 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_change_tool_frame(rm_robot_handle *handle, const char* tool_name); +/** + * @brief 删除指定工具坐标系 + * + * @param handle 机械臂句柄 + * @param tool_name 要删除的工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_tool_frame(rm_robot_handle *handle, const char* tool_name); +/** + * @brief 修改指定工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame 要修改的工具坐标系参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_tool_frame(rm_robot_handle *handle, rm_frame_t frame); +/** + * @brief 获取所有工具坐标系名称 + * + * @param handle 机械臂控制句柄 + * @param frame_names 返回的工具坐标系名称字符数组 + * @param len 返回的工具坐标系名称长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_total_tool_frame(rm_robot_handle *handle, rm_frame_name_t *frame_names, int *len); +/** + * @brief 获取指定工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param name 指定的工具坐标系名称 + * @param frame 返回的工具参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。可能情况:查询的工具坐标系不存在 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_tool_frame(rm_robot_handle *handle, const char *name, rm_frame_t *frame); +/** + * @brief 获取当前工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param tool_frame 返回的坐标系 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_tool_frame(rm_robot_handle *handle, rm_frame_t *tool_frame); +/** + * @brief 设置工具坐标系的包络参数 + * + * @param handle 机械臂控制句柄 + * @param envelope 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_envelope(rm_robot_handle *handle, rm_envelope_balls_list_t envelope); +/** + * @brief 获取工具坐标系的包络参数 + * + * @param handle 机械臂控制句柄 + * @param tool_name 控制器中已存在的工具坐标系名称 + * @param envelope 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回获取失败,可能情况:获取的工具坐标系不存在。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_envelope(rm_robot_handle *handle, const char* tool_name, rm_envelope_balls_list_t *envelope); +/** @} */ // 结束组的定义 + +/** + * @defgroup WorkCoordinateConfig 工作坐标系配置 + * + * 工作坐标系标定、切换、删除、修改、查询等管理 + * @{ + */ +/** + * @brief 三点法自动设置工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param workname 工作坐标系名称,不能超过十个字节。 + * @param point_num 1~3代表3个标定点,依次为原点、X轴一点、Y轴一点,4代表生成坐标系。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_auto_work_frame(rm_robot_handle *handle,const char *workname, int point_num); +/** + * @brief 手动设置工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 工作坐标系名称,不能超过十个字节。 + * @param pose 新工作坐标系相对于基坐标系的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_manual_work_frame(rm_robot_handle *handle, const char* work_name, rm_pose_t pose); +/** + * @brief 切换当前工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 目标工作坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_change_work_frame(rm_robot_handle *handle, const char* work_name); +/** + * @brief 删除指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 要删除的工作坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_work_frame(rm_robot_handle *handle, const char* work_name); +/** + * @brief 修改指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 指定工具坐标系名称 + * @param pose 更新工作坐标系相对于基坐标系的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_work_frame(rm_robot_handle *handle, const char* work_name, rm_pose_t pose); +/** + * @brief 获取所有工作坐标系名称 + * + * @param handle 机械臂控制句柄 + * @param frame_names 返回的工作坐标系名称字符数组 + * @param len 返回的工作坐标系名称长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_total_work_frame(rm_robot_handle *handle, rm_frame_name_t *frame_names, int *len); +/** + * @brief 获取指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param name 指定的工作坐标系名称 + * @param pose 获取到的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。例如:查询的工具坐标系不存在 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_work_frame(rm_robot_handle *handle, const char *name, rm_pose_t *pose); +/** + * @brief 获取当前工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_frame 返回的坐标系 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_work_frame(rm_robot_handle *handle, rm_frame_t *work_frame); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmState 机械臂状态查询 + * + * 机械臂当前状态、关节温度、电流、电压查询 + * @{ + */ +/** + * @brief 获取机械臂当前状态 + * + * @param handle 机械臂控制句柄 + * @param state 机械臂当前状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_arm_state(rm_robot_handle *handle,rm_current_arm_state_t *state); +/** + * @brief 获取关节当前温度 + * + * @param handle 机械臂控制句柄 + * @param temperature 关节1~7温度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_temperature(rm_robot_handle *handle, float *temperature); +/** + * @brief 获取关节当前电流 + * + * @param handle 机械臂控制句柄 + * @param current 关节1~7电流数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_current(rm_robot_handle *handle, float *current); +/** + * @brief 获取关节当前电压 + * + * @param handle 机械臂控制句柄 + * @param voltage 关节1~7电压数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_voltage(rm_robot_handle *handle, float *voltage); +/** + * @brief 获取当前关节角度 + * + * @param handle 机械臂控制句柄 + * @param joint 当前7个关节的角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_degree(rm_robot_handle *handle, float *joint); +/** + * @brief 获取机械臂所有状态信息 + * + * @param handle 机械臂控制句柄 + * @param state 存储机械臂信息的结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_all_state(rm_robot_handle *handle, rm_arm_all_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup InitPose 初始位置设置 + * + * 记录机械臂初始位置 + * @{ + */ +/** + * @brief 设置机械臂的初始位置角度 + * + * @param handle 机械臂控制句柄 + * @param joint 机械臂初始位置关节角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_init_pose(rm_robot_handle *handle, float *joint); +/** + * @brief 获取机械臂初始位置角度 + * + * @param handle 机械臂控制句柄 + * @param joint 机械臂初始位置关节角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_init_pose(rm_robot_handle *handle, float *joint); +/** @} */ // 结束组的定义 + +/** + * @defgroup MovePlan 机械臂轨迹指令类 + * + * 关节运动、笛卡尔空间运动以及角度及位姿透传 + * @{ + */ +/** + * @brief 关节空间运动 + * + * @param handle 机械臂控制句柄 + * @param joint 目标关节1~7角度数组 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movej(rm_robot_handle *handle, const float *joint, int v, int r,int trajectory_connect,int block); +/** + * @brief 笛卡尔空间直线运动 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movel(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 笛卡尔空间偏移运动(四代控制器支持) + * @details 该函数用于机械臂末端在当前位姿的基础上沿某坐标系(工具或工作)进行位移或旋转运动。 + * @param handle 机械臂控制句柄 + * @param offset 位置姿态偏移,位置单位:米,姿态单位:弧度 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param frame_type 参考坐标系类型:0-工作,1-工具 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movel_offset(rm_robot_handle *handle,rm_pose_t offset, int v, int r, int trajectory_connect, int frame_type, int block); +/** + * @brief 样条曲线运动 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @note 样条曲线运动需至少连续下发三个点位(trajectory_connect设置为1),否则运动轨迹为直线 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_moves(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 笛卡尔空间圆弧运动 + * + * @param handle 机械臂控制句柄 + * @param pose_via 中间点位姿,位置单位:米,姿态单位:弧度 + * @param pose_to 终点位姿 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + * @param r 交融半径百分比系数,0~100。 + * @param loop 规划圈数. + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movec(rm_robot_handle *handle,rm_pose_t pose_via, rm_pose_t pose_to, int v, int r, int loop, int trajectory_connect, int block); +/** + * @brief 该函数用于关节空间运动到目标位姿 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度。 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movej_p(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 角度不经规划,直接通过CANFD透传给机械臂 + * @details 角度透传到 CANFD,若指令正确,机械臂立即执行 + * 备注: + * 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + * 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + * I系列有线网口周期最快可达2ms,提供了更高的实时性。 + * @param handle 机械臂控制句柄 + * @param config 角度透传模式配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movej_canfd(rm_robot_handle *handle, rm_movej_canfd_mode_t config); +/** + * @brief 位姿不经规划,直接通过CANFD透传给机械臂 + * @details 当目标位姿被透传到机械臂控制器时,控制器首先尝试进行逆解计算。 + * 若逆解成功且计算出的各关节角度与当前角度差异不大,则直接下发至关节执行,跳过额外的轨迹规划步骤。 + * 这一特性适用于需要周期性调整位姿的场景,如视觉伺服等应用。 + * 备注: + * 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + * 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + * I系列有线网口周期最快可达2ms,提供了更高的实时性。 + * @param handle 机械臂控制句柄 + * @param config 姿态透传模式结构体 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movep_canfd(rm_robot_handle *handle, rm_movep_canfd_mode_t config); +/** + * @brief 关节空间跟随运动 + * @param handle 机械臂控制句柄 + * @param joint 关节1~7目标角度数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movej_follow(rm_robot_handle *handle,float *joint); +/** + * @brief 笛卡尔空间跟随运动 + * @param handle 机械臂控制句柄 + * @param pose 位姿 (优先采用四元数表达) + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movep_follow(rm_robot_handle *handle, rm_pose_t pose); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmMotionControl 机械臂运动控制指令类 + * + * 控制运动的急停、缓停、暂停、继续、清除轨迹以及查询当前规划类型 + * @{ + */ +/** + * @brief 轨迹缓停,在当前正在运行的轨迹上停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_slow_stop(rm_robot_handle *handle); +/** + * @brief 轨迹急停,关节最快速度停止,轨迹不可恢复 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_stop(rm_robot_handle *handle); +/** + * @brief 轨迹暂停,暂停在规划轨迹上,轨迹可恢复 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_pause(rm_robot_handle *handle); +/** + * @brief 轨迹暂停后,继续当前轨迹运动 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_continue(rm_robot_handle *handle); +/** + * @brief 清除当前轨迹 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 必须在暂停后使用,否则机械臂会发生意外!!!! + */ +RM_INTERFACE_EXPORT int rm_set_delete_current_trajectory(rm_robot_handle *handle); +/** + * @brief 清除所有轨迹 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 必须在暂停后使用,否则机械臂会发生意外!!!! + */ +RM_INTERFACE_EXPORT int rm_set_arm_delete_trajectory(rm_robot_handle *handle); +/** + * @brief 获取当前正在规划的轨迹信息 + * + * @param handle 机械臂控制句柄 + * @param type 返回的规划类型 + * @param data 无规划和关节空间规划为当前关节1~7角度数组;笛卡尔空间规划则为当前末端位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_current_trajectory(rm_robot_handle *handle,rm_arm_current_trajectory_e *type,float *data); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmTeachMove 机械臂示教指令类 + * + * 关节、位置、姿态的示教及步进控制 + * @{ + */ +/** + * @brief 关节步进 + * + * @param handle 机械臂控制句柄 + * @param joint_num 关节序号,1~7 + * @param step 步进的角度, + * @param v 速度百分比系数,1~100 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_step(rm_robot_handle *handle,int joint_num, float step, int v, int block); +/** + * @brief 当前工作坐标系下,位置步进 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param step 步进的距离,单位m,精确到0.001mm + * @param v 速度百分比系数,1~100 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_pos_step(rm_robot_handle *handle, rm_pos_teach_type_e type, float step, int v, int block); +/** + * @brief 当前工作坐标系下,姿态步进 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param step 步进的弧度,单位rad,精确到0.001rad + * @param v 速度百分比系数,1~100 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_ort_step(rm_robot_handle *handle, rm_ort_teach_type_e type, float step, int v, int block); +/** + * @brief 切换示教运动坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame_type 0: 工作坐标系运动, 1: 工具坐标系运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_teach_frame(rm_robot_handle *handle, int frame_type); +/** + * @brief 获取示教参考坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame_type 0: 工作坐标系运动, 1: 工具坐标系运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_teach_frame(rm_robot_handle *handle,int *frame_type); +/** + * @brief 关节示教 + * + * @param handle 机械臂控制句柄 + * @param joint_num 示教关节的序号,1~7 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_teach(rm_robot_handle *handle,int joint_num, int direction, int v); +/** + * @brief 当前工作坐标系下,笛卡尔空间位置示教 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_pos_teach(rm_robot_handle *handle,rm_pos_teach_type_e type, int direction, int v); +/** + * @brief 当前工作坐标系下,笛卡尔空间姿态示教 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_ort_teach(rm_robot_handle *handle,rm_ort_teach_type_e type, int direction, int v); +/** + * @brief 示教停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_stop_teach(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ControllerConfig 系统配置 + * + * 控制器状态获取、电源控制、错误清除、有线网口IP地址配置、软件信息获取 + * @{ + */ +/** + * @brief 获取控制器状态 + * + * @param handle 机械臂控制句柄 + * @param voltage 返回的电压 + * @param current 返回的电流 + * @param temperature 返回的温度 + * @param err_flag 控制器运行错误代码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_controller_state(rm_robot_handle *handle, float *voltage, float *current, float *temperature, int *err_flag); +/** + * @brief 设置机械臂电源 + * + * @param handle 机械臂控制句柄 + * @param arm_power 1-上电状态,0 断电状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_power(rm_robot_handle *handle, int arm_power); +/** + * @brief 读取机械臂电源状态 + * + * @param handle 机械臂控制句柄 + * @param power_state 获取到的机械臂电源状态,1-上电状态,0 断电状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_power_state(rm_robot_handle *handle, int *power_state); +/** + * @brief 读取控制器的累计运行时间 + * + * @param handle 机械臂控制句柄 + * @param day 读取到的时间 + * @param hour 读取到的时间 + * @param min 读取到的时间 + * @param sec 读取到的时间 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_system_runtime(rm_robot_handle *handle, int *day, int *hour, int *min, int *sec); +/** + * @brief 清零控制器的累计运行时间 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_system_runtime(rm_robot_handle *handle); +/** + * @brief 读取关节的累计转动角度 + * + * @param handle 机械臂控制句柄 + * @param joint_odom 各关节累计的转动角度,单位° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_odom(rm_robot_handle *handle, float *joint_odom); +/** + * @brief 清零关节累计转动的角度 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_joint_odom(rm_robot_handle *handle); +/** + * @brief 配置有线网口 IP 地址 + * + * @param handle 机械臂控制句柄 + * @param ip 有线网口 IP 地址 + * @param netmask 有线网口子网掩码 + * @param gw 有线网口网关地址 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_NetIP(rm_robot_handle *handle, const char* ip, const char* netmask, const char* gw); +/** + * @brief 清除系统错误 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_system_err(rm_robot_handle *handle); +/** + * @brief 读取机械臂软件信息 + * + * @param handle 机械臂控制句柄 + * @param software_info 机械臂软件信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_software_info(rm_robot_handle *handle,rm_arm_software_version_t *software_info); +/** + * @brief 查询控制器RS485模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0-代表默认 RS485 串行通讯,1-代表 modbus-RTU 主站模式,2-代表 modbus-RTU 从站模式; + * @param baudrate 波特率 + * @param timeout modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_controller_RS485_mode(rm_robot_handle *handle, int* mode, int* baudrate, int* timeout); +/** + * @brief 查询工具端 RS485 模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0-代表默认 RS485 串行通讯 1-代表 modbus-RTU 主站模式 + * @param baudrate 波特率 + * @param timeout modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_tool_RS485_mode(rm_robot_handle *handle, int* mode, int* baudrate, int* timeout); +/** + * @brief 查询关节软件版本号 + * + * @param handle 机械臂控制句柄 + * @param version (三代控制器)获取到的各关节软件版本号数组,需转换为十六进制,例如获取某关节版本为54536,转换为十六进制为D508,则当前关节的版本号为 Vd5.0.8 + * @param joint_v (四代控制器)获取到的各关节软件版本号字符串数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_software_version(rm_robot_handle *handle,int *version, rm_version_t *joint_v); +/** + * @brief 查询末端接口板软件版本号 + * + * @param handle 机械臂控制句柄 + * @param version (三代控制器)获取到的末端接口板软件版本号,需转换为十六进制,例如获取到版本号393,转换为十六进制为189,则当前关节的版本号为 V1.8.9 + * @param tool_v (四代控制器)获取到的末端接口板软件版本号字符串 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_software_version(rm_robot_handle *handle, int *version, rm_version_t *tool_v); +/** @} */ // 结束组的定义 + +/** + * @defgroup CommunicationConfig 配置通讯内容 + * + * 机械臂控制器可通过网口、WIFI、RS232-USB 接口和 RS485 接口与用户通信,用户使用时无需切换,可使用上述任一接口, + * 控制器收到指令后,若指令格式正确,则会通过相同的接口反馈数据。 + * @{ + */ +/** + * @brief 配置 wifiAP 模式 + * + * @param handle 机械臂控制句柄 + * @param wifi_name wifi名称 + * @param password wifi密码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + * @attention 设置成功后蜂鸣器响,手动重启控制器进入 WIFIAP 模式。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_ap(rm_robot_handle *handle, const char* wifi_name, const char* password); +/** + * @brief 配置WiFi STA模式 + * + * @param handle 机械臂控制句柄 + * @param router_name 路由器名称 + * @param password 路由器Wifi密码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + * @attention 设置成功后蜂鸣器响,手动重启控制器进入 WIFISTA 模式。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_sta(rm_robot_handle *handle, const char* router_name, const char* password); + +/** + * @brief 控制器RS485接口波特率设置,设置成功后蜂鸣器响 + * + * @param handle 机械臂控制句柄 + * @param baudrate 波特率:9600,19200,38400,115200和460800,若用户设置其他数据,控制器会默认按照460800处理。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 四代控制器不支持该接口 + * @attention 该指令下发后控制器会记录当前波特率,断电重启后仍会使用该波特率对外通信。 + */ +RM_INTERFACE_EXPORT int rm_set_RS485(rm_robot_handle *handle, int baudrate); +/** + * @brief 获取有线网卡信息,未连接有线网卡则会返回无效数据 + * + * @param handle 机械臂控制句柄 + * @param ip 网络地址 + * @param mask 子网掩码 + * @param mac MAC地址 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_wired_net(rm_robot_handle *handle, char * ip, char * mask, char * mac); +/** + * @brief 查询无线网卡网络信息 + * + * @param handle 机械臂控制句柄 + * @param wifi_net 无线网卡网络信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 结构体中的channel值只有在AP模式时才可获取到,标识 wifi 热点的物理信道号 + */ +RM_INTERFACE_EXPORT int rm_get_wifi_net(rm_robot_handle *handle, rm_wifi_net_t *wifi_net); +/** + * @brief 恢复网络出厂设置 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_net_default(rm_robot_handle *handle); +/** + * @brief 配置关闭 wifi 功能,需要重启后生效 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_close(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ControllerIOConfig 控制器IO配置及获取 + * + * 机械臂控制器提供IO端口,用于与外部设备交互。数量和分类如下所示: + * + * @image html io.png + * @{ + */ +/** + * @brief 设置数字IO模式 + * + * @param handle 机械臂控制句柄 + * @param io_num 数字IO端口号,范围:1~4 + * @param config 数字IO配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_IO_mode(rm_robot_handle *handle, int io_num, rm_io_config_t config); +/** + * @brief 设置数字IO输出 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~4 + * @param state IO 状态,1-输出高,0-输出低 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DO_state(rm_robot_handle *handle, int io_num, int state); +/** + * @brief 获取数字 IO 状态 + * + * @param handle 机械臂控制句柄 + * @param config 数字IO配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_state(rm_robot_handle *handle, int io_num, rm_io_get_t* config); +/** + * @brief 获取所有 IO 输入状态 + * + * @param handle 机械臂控制句柄 + * @param DI_state 1~4端口数字输入状态数组,1:高,0:低,-1:该端口不是输入模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_input(rm_robot_handle *handle, int *DI_state); +/** + * @brief 获取所有 IO 输出状态 + * + * @param handle 机械臂控制句柄 + * @param DO_state 1~4端口数字输出状态数组,1:高,0:低,-1:该端口不是输出模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_output(rm_robot_handle *handle, int *DO_state); +/** + * @brief 设置控制器电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,2:12V,3:24V + * @param start_enable true:开机启动时输出此配置电压,false:取消开机启动即配置电压 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_voltage(rm_robot_handle *handle, int voltage_type, bool start_enable); +/** + * @brief 获取控制器电源输出类 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,2:12V,3:24V + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_voltage(rm_robot_handle *handle, int *voltage_type); +/** @} */ // 结束组的定义 + +/** + * @defgroup ToolIOConfig 末端工具 IO 控制 + * + * 机械臂末端工具端提供多种IO端口,用于与外部设备交互。数量和分类如下所示: + * @image html tool_io.png + * @{ + */ +/** + * @brief 设置工具端数字 IO 输出 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~2 + * @param state IO 状态,1-输出高,0-输出低 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_DO_state(rm_robot_handle *handle, int io_num, int state); +/** + * @brief 设置工具端数字 IO 模式 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~2 + * @param io_mode 模式,0-输入状态,1-输出状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_IO_mode(rm_robot_handle *handle, int io_num, int io_mode); +/** + * @brief 获取数字 IO 状态 + * + * @param handle 机械臂控制句柄 + * @param mode 0-输入模式,1-输出模式 + * @param state 0-低,1-高 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_IO_state(rm_robot_handle *handle, int* mode, int* state); +/** + * @brief 设置工具端电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,1:5V,2:12V,3:24V, + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 电源输出设置为 5V 时,工具端的IO 暂不支持输入输出功能 + */ +RM_INTERFACE_EXPORT int rm_set_tool_voltage(rm_robot_handle *handle, int voltage_type); +/** + * @brief 获取工具端电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,1:5V,2:12V,3:24V, + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_voltage(rm_robot_handle *handle, int *voltage_type); +/** @} */ // 结束组的定义 + +/** + * @defgroup GripperControl 末端工具—手爪控制 + * + * 睿尔曼机械臂末端配备了因时机器人公司的 EG2-4C2 手爪,为了便于用户操作手爪,机械臂控制器 + * 对用户开放了手爪的控制协议(手爪控制协议与末端modbus 功能互斥) + * @{ + */ +/** + * @brief 设置手爪行程,即手爪开口的最大值和最小值,设置成功后会自动保存,手爪断电不丢失 + * + * @param handle 机械臂控制句柄 + * @param min_limit 手爪开口最小值,范围:0~1000,无单位量纲 + * @param max_limit 手爪开口最大值,范围:0~1000,无单位量纲 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_route(rm_robot_handle *handle, int min_limit, int max_limit); +/** + * @brief 松开手爪,即手爪以指定的速度运动到开口最大处 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪松开速度,范围 1~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 到位设备检验失败 + - -5: 超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_release(rm_robot_handle *handle, int speed, bool block, int timeout); +/** + * @brief 手爪力控夹取,手爪以设定的速度和力夹取,当夹持力超过设定的力阈值后,停止夹取 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪夹取速度,范围 1~1000,无单位量纲 + * @param force 力控阈值,范围:50~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 到位设备检验失败 + - -5: 超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_pick(rm_robot_handle *handle, int speed, int force, bool block, int timeout); +/** + * @brief 手爪持续力控夹取 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪夹取速度,范围 1~1000,无单位量纲 + * @param force 力控阈值,范围:50~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 到位设备检验失败 + - -5: 超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_pick_on(rm_robot_handle *handle, int speed, int force, bool block, int timeout); +/** + * @brief 设置手爪达到指定位置 + * @details 手爪到达指定位置,当当前开口小于指定开口时,手爪以指定速度松开到指定开口位置;当当前开口大于指定开口时, + * 手爪以指定速度和力矩闭合往指定开口处闭合,当夹持力超过力矩阈值或者达到指定位置后,手爪停止。 + * @param handle 机械臂控制句柄 + * @param position 手爪开口位置,范围:1~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 到位设备检验失败 + - -5: 超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_position(rm_robot_handle *handle, int position, bool block, int timeout); +/** + * @brief 查询夹爪状态 + * + * @param handle 机械臂控制句柄 + * @param state 夹爪状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 此接口默认不更新数据,从首次控制夹爪开始后,使能更新状态,如果此时控制灵巧手或打开末端modbus功能,将不再更新数据。另外夹爪需要支持最新的固件,方可支持此功能 + */ +RM_INTERFACE_EXPORT int rm_get_gripper_state(rm_robot_handle *handle, rm_gripper_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForceSensor 末端传感器六维力 + * + * 睿尔曼机械臂六维力版末端配备集成式六维力传感器,无需外部走线,用户可直接通过协议对六维力进行操作, + * 获取六维力数据。如下图所示,正上方为六维力的 Z 轴,航插反方向为六维力的 Y 轴,坐标系符合右手定则。 + * 机械臂位于零位姿态时,工具坐标系与六维力的坐标系方向一致。 + * 另外,六维力额定力 200N,额定力矩 8Nm,过载水平 300%FS,工作温度 5~80℃,准度 0.5%FS。使用过程中 + * 注意使用要求,防止损坏六维力传感器。 + * + * @image html force.png "六维力坐标系" + * @{ + */ +/** + * @brief 查询当前六维力传感器得到的力和力矩信息:Fx,Fy,Fz,Mx,My,Mz + * + * @param handle 机械臂控制句柄 + * @param data 力传感器数据结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。可能情况:当前机械臂不是六维力版本。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_force_data(rm_robot_handle *handle, rm_force_data_t *data); +/** + * @brief 将六维力数据清零,标定当前状态下的零位 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_force_data(rm_robot_handle *handle); +/** + * @brief 自动设置六维力重心参数 + * @details 设置六维力重心参数,六维力重新安装后,必须重新计算六维力所受到的初始力和重心。分别在不同姿态下,获取六维力的数据, + * 用于计算重心位置。该指令下发后,机械臂以固定的速度运动到各标定点。 + * 以RM65机械臂为例,四个标定点的关节角度分别为: + * 位置1关节角度:{0,0,-60,0,60,0} + * 位置2关节角度:{0,0,-60,0,-30,0} + * 位置3关节角度:{0,0,-60,0,-30,180} + * 位置4关节角度:{0,0,-60,0,-120,0} + * @attention 必须保证在机械臂静止状态下标定; + * 该过程不可中断,中断后必须重新标定。 + * @param handle 机械臂控制句柄 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_sensor(rm_robot_handle *handle, bool block); +/** + * @brief 手动标定六维力数据 + * @details 六维力重新安装后,必须重新计算六维力所受到的初始力和重心。该手动标定流程,适用于空间狭窄工作区域,以防自动标定过程中 + * 机械臂发生碰撞,用户可以手动选取四个位置下发,当下发完四个点后,机械臂开始自动沿用户设置的目标运动,并在此过程中计算六维力重心。 + * @attention 上述4个位置必须按照顺序依次下发,当下发完位置4后,机械臂开始自动运行计算重心。 + * @param handle 机械臂控制句柄 + * @param count 点位;1~4 + * @param joint 关节角度,单位:° + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 计算成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_manual_set_force(rm_robot_handle *handle, int count, float *joint, bool block); +/** + * @brief 停止标定力传感器重心 + * @details 在标定力传感器过程中,如果发生意外,发送该指令,停止机械臂运动,退出标定流程 + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_set_force_sensor(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup OneForceSensor 末端传感器一维力 + * + * 睿尔曼机械臂末端接口板集成了一维力传感器,可获取 Z 方向的力,量程200N,准度 0.5%FS。 + * @image html oneforce.png "一维力坐标系" + * @{ + */ +/** + * @brief 查询末端一维力数据 + * + * @param handle 机械臂控制句柄 + * @param data 一维力数据结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非力控版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_get_Fz(rm_robot_handle *handle, rm_fz_data_t *data); +/** + * @brief 清零末端一维力数据,清空一维力数据后,后续所有获取到的数据都是基于当前的偏置。 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_Fz(rm_robot_handle *handle); +/** + * @brief 自动标定一维力数据 + * @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。 + * 分别在不同姿态下,获取一维力的数据,用于计算重心位置,该步骤对于基于一维力的力位混合控制操作具有重要意义。 + * @param handle 机械臂控制句柄 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_auto_set_Fz(rm_robot_handle *handle, bool block); +/** + * @brief 手动标定一维力数据 + * @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。该手动标定流程, + * 适用于空间狭窄工作区域,以防自动标定过程中机械臂发生碰撞,用户可以手动选取2个位置下发,当下发完后, + * 机械臂开始自动沿用户设置的目标运动,并在此过程中计算一维力重心。 + * @param handle 机械臂控制句柄 + * @param joint1 位置1关节角度数组,单位:度 + * @param joint2 位置2关节角度数组,单位:度 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_manual_set_Fz(rm_robot_handle *handle, float *joint1, float *joint2, bool block); +/** @} */ // 结束组的定义 + +/** + * @defgroup DragTeach 拖动示教 + * + * 睿尔曼机械臂在拖动示教过程中,可记录拖动的轨迹点,并根据用户的指令对轨迹进行复现。 + * @{ + */ +/** + * @brief 拖动示教开始 + * + * @param handle 机械臂控制句柄 + * @param trajectory_record 拖动示教时记录轨迹,0-不记录,1-记录轨迹 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_start_drag_teach(rm_robot_handle *handle, int trajectory_record); +/** + * @brief 拖动示教结束 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_drag_teach(rm_robot_handle *handle); +/** + * @brief 开始复合模式拖动示教 + * @attention 仅支持三代控制器,四代控制器使用rm_start_multi_drag_teach_new + * @param handle 机械臂控制句柄 + * @param mode 拖动示教模式 0-电流环模式,1-使用末端六维力,只动位置,2-使用末端六维力,只动姿态,3-使用末端六维力,位置和姿态同时动 + * @param singular_wall 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口。 + * @note 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + */ +RM_INTERFACE_EXPORT int rm_start_multi_drag_teach(rm_robot_handle *handle, int mode, int singular_wall); +/** + * @brief 开始复合模式拖动示教-新参数 + * + * @param handle 机械臂控制句柄 + * @param teach_state 复合拖动示教参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @note 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + */ +RM_INTERFACE_EXPORT int rm_start_multi_drag_teach_new(rm_robot_handle *handle,rm_multi_drag_teach_t teach_state); +/** + * @brief 设置电流环拖动示教灵敏度 + * + * @param handle 机械臂控制句柄 + * @param grade 等级,0到100,表示0~100%,当设置为100时保持初始状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_drag_teach_sensitivity(rm_robot_handle *handle, int grade); +/** + * @brief 获取电流环拖动示教灵敏度 + * + * @param handle 机械臂控制句柄 + * @param grade 等级,0到100,表示0~100%,当设置为100时保持初始状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_drag_teach_sensitivity(rm_robot_handle *handle, int *grade); +/** + * @brief 运动到轨迹起点 + * @details 轨迹复现前,必须控制机械臂运动到轨迹起点,如果设置正确,机械臂将以20%的速度运动到轨迹起点 + * @param handle 机械臂控制句柄 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @see rm_run_drag_trajectory + */ +RM_INTERFACE_EXPORT int rm_drag_trajectory_origin(rm_robot_handle *handle, int block); +/** + * @brief 轨迹复现开始 + * + * @param handle 机械臂控制句柄 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误,请确保机械臂当前位置为拖动示教起点。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 必须在拖动示教结束后才能使用,同时保证机械臂位于拖动示教的起点位置,可调用rm_drag_trajectory_origin接口运动至起点位置 + * @see rm_drag_trajectory_origin + */ +RM_INTERFACE_EXPORT int rm_run_drag_trajectory(rm_robot_handle *handle, int block); +/** + * @brief 控制机械臂在轨迹复现过程中的暂停 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_pause_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 控制机械臂在轨迹复现过程中暂停之后的继续, + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_continue_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 控制机械臂在轨迹复现过程中的停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 保存拖动示教轨迹 + * + * @param handle 机械臂控制句柄 + * @param name 轨迹要保存的文件路径及名称,长度不超过300个字符,例: c:/rm_test.txt + * @param num 轨迹点数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,确保有拖动示教点位可保存。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 文件打开失败 + - -5: 文件名称截取失败 + - -6: 获取到的点位解析错误,保存失败 + */ +RM_INTERFACE_EXPORT int rm_save_trajectory(rm_robot_handle *handle,const char* name, int *num); +/** + * @brief 力位混合控制 + * @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + * 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + * @param handle 机械臂控制句柄 + * @param sensor 0-一维力;1-六维力 + * @param mode 0-基坐标系力控;1-工具坐标系力控; + * @param direction 力控方向;0-沿X轴;1-沿Y轴;2-沿Z轴;3-沿RX姿态方向;4-沿RY姿态方向;5-沿RZ姿态方向 + * @param N 力的大小,单位N + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_position(rm_robot_handle *handle, int sensor, int mode, int direction, float N); +/** + * @brief 力位混合控制-新参数 + * @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + * 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + * @param handle 机械臂控制句柄 + * @param param 力位混合控制参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_position_new(rm_robot_handle *handle, rm_force_position_t param); + +/** + * @brief 结束力位混合控制 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_force_position(rm_robot_handle *handle); +/** + * @brief 设置六维力拖动示教模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0表示快速拖动模式 1表示精准拖动模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_set_force_drag_mode(rm_robot_handle *handle, int mode); +/** + * @brief 获取六维力拖动示教模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0表示快速拖动模式 1表示精准拖动模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。处理建议:1、联系睿尔曼公司技术支持确认控制器版本是否支持此功能; + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_get_force_drag_mode(rm_robot_handle *handle, int *mode); +/** @} */ // 结束组的定义 + +/** + * @defgroup HandControl 五指灵巧手 + * + * 睿尔曼机械臂末端配置因时的五指灵巧手,可通过协议对灵巧手进行设置。 + * @{ + */ +/** + * @brief 设置灵巧手目标手势序列号 + * + * @param handle 机械臂控制句柄 + * @param posture_num 预先保存在灵巧手内的手势序号,范围:1~40 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_posture(rm_robot_handle *handle, int posture_num, bool block, int timeout); +/** + * @brief 设置灵巧手目标手势序列号 + * + * @param handle 机械臂控制句柄 + * @param seq_num 预先保存在灵巧手内的手势序号,范围:1~40 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_seq(rm_robot_handle *handle, int seq_num, bool block, int timeout); +/** + * @brief 设置灵巧手各自由度角度 + * @details 设置灵巧手角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + * @param handle 机械臂控制句柄 + * @param hand_angle 手指角度数组,6个元素分别代表6个自由度的角度,范围:0~1000. 另外,-1代表该自由度不执行任何操作,保持当前状态 + * @param block 0:表示非阻塞模式,发送成功后返回,1:表示阻塞模式,接收设置成功指令后返回。 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_angle(rm_robot_handle *handle, const int *hand_angle, bool block, int timeout); +/** + * @brief 设置灵巧手角度跟随控制 + * @details 设置灵巧手跟随角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转,最高50Hz的控制频率 + * @param handle 机械臂控制句柄 + * @param hand_angle 手指角度数组,最大表示范围为-32768到+32767,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-2000 + * @param block 设置0时为非阻塞模式;设置1时为阻塞模式,阻塞模式时超时20ms未返回认为接受失败。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_follow_angle(rm_robot_handle *handle, const int *hand_angle, bool block); +/** + * @brief 灵巧手位置跟随控制 + * @details 设置灵巧手跟随位置,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转,最高50Hz的控制频率 + * @param handle 机械臂控制句柄 + * @param hand_pos 手指位置数组,最大范围为0-65535,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-1000 + * @param block 0:表示非阻塞模式,发送成功后返回,1:表示阻塞模式,接收设置成功指令后返回。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_follow_pos(rm_robot_handle *handle, const int *hand_pos, bool block); +/** + * @brief 设置灵巧手速度 + * + * @param handle 机械臂控制句柄 + * @param speed 手指速度,范围:1~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_speed(rm_robot_handle *handle, int speed); +/** + * @brief 设置灵巧手力阈值 + * + * @param handle 机械臂控制句柄 + * @param hand_force 手指力,范围:1~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_force(rm_robot_handle *handle, int hand_force); +/** @} */ // 结束组的定义 + +/** + * @defgroup ModbusConfig Modbus 配置 + * + * 睿尔曼机械臂在控制器和末端接口板上各提供一个RS485通讯接口,这些接口可通过接口配置为标准的Modbus RTU模式。 + * 在Modbus RTU模式下,用户可通过提供的接口对连接在端口上的外设进行读写操作。 + * + * @attention + * - 控制器的RS485接口在未配置为Modbus RTU模式时,可用于直接控制机械臂。 + * - Modbus RTU模式与机械臂控制模式不兼容。若需恢复机械臂控制模式,必须关闭该端口的Modbus RTU模式。 + * - 关闭Modbus RTU模式后,系统将自动切换回机械臂控制模式,使用波特率460800BPS,停止位1,数据位8,无校验。 + * + * 此外,I系列控制器还支持modbus-TCP主站配置,允许用户配置使用modbus-TCP主站,以连接外部设备的modbus-TCP从站。 + * + * @{ + */ +/** + * @brief 配置通讯端口ModbusRTU模式 + * @details 配置通讯端口ModbusRTU模式,机械臂启动后,要对通讯端口进行任何操作,必须先启动该指令,否则会返回报错信息。 + * 另外,机械臂会对用户的配置方式进行保存,机械臂重启后会自动恢复到用户断电之前配置的模式。 + * @param handle 机械臂控制句柄 + * @param port 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + * @param baudrate 波特率,支持 9600,115200,460800 三种常见波特率 + * @param timeout 超时时间,单位百毫秒。。对Modbus设备所有的读写指令,在规定的超时时间内未返回响应数据,则返回超时报错提醒。超时时间不能为0,若设置为0,则机械臂按1进行配置。 + * @note 其他配置默认为:数据位-8,停止位-1,奇偶校验-无 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_modbus_mode(rm_robot_handle *handle, int port, int baudrate, int timeout); +/** + * @brief 关闭通讯端口 Modbus RTU 模式 + * + * @param handle 机械臂控制句柄 + * @param port 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_close_modbus_mode(rm_robot_handle *handle, int port); +/** + * @brief 配置连接 ModbusTCP 从站 + * + * @attention 如需配置连接ModbusTCP从站,则该接口需要在创建机械臂句柄后调用一次,否则在读写寄存器时无法接收到返回值。 + * @param handle 机械臂控制句柄 + * @param ip 从机IP地址 + * @param port 端口号 + * @param timeout 超时时间,单位毫秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_modbustcp_mode(rm_robot_handle *handle, const char *ip, int port, int timeout); +/** + * @brief 配置关闭 ModbusTCP 从站 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_close_modbustcp_mode(rm_robot_handle *handle); +/** + * @brief 读线圈 + * + * @param handle 机械臂控制句柄 + * @param params 线圈读取参数结构体,该指令最多一次性支持读 8 个线圈数据,即返回的数据不会超过一个字节 + * @param data 返回线圈状态,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读离散量输入 + * + * @param handle 机械臂控制句柄 + * @param params 离散量输入读取参数结构体,该指令最多一次性支持读 8 个离散量数据,即返回的数据不会超过一个字节 + * @param data 返回离散量,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_input_status(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读保持寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 保持寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节 + * 的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + * @param data 返回寄存器数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_holding_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读输入寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 输入寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节 + * 的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + * @param data 返回寄存器数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_input_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 写单圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 单圈数据写入参数结构体,该结构体成员num无需设置 + * @param data 要写入线圈的数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_single_coil(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int data); +/** + * @brief 写单个寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 单个寄存器数据写入参数结构体,该结构体成员num无需设置 + * @param data 要写入寄存器的数据,类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_single_register(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int data); +/** + * @brief 写多个寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个寄存器数据写入参数结构体。其中寄存器每次写的数量不超过10个,即该结构体成员num<=10。 + * @param data 要写入寄存器的数据数组,类型:byte。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 写多圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 多圈数据写入参数结构体。每次写的数量不超过 160 个,即该结构体成员num<=160。 + * @param data 要写入线圈的数据数组,类型:byte。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 多圈数据读取参数结构体,要读的线圈的数量 8< num <= 120,该指令最多一次性支持读 120 个线圈数据, 即 15 个 byte + * @param data 返回线圈状态,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多个保存寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个保存寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + * @param data 返回寄存器数据,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_holding_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多个输入寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个输入寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + * @param data 返回寄存器数据,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_input_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** @} */ // 结束组的定义 + +/** + * @defgroup InstallPos 系统安装方式 + * + * 睿尔曼机械臂可支持不同形式的安装方式,但是安装方式不同,机器人的动力学模型参数和坐标系的方向也有所差别。 + * @{ + */ +/** + * @brief 设置安装方式参数 + * + * @param handle 机械臂控制句柄 + * @param x 旋转角,单位 ° + * @param y 俯仰角,单位 ° + * @param z 方位角,单位 ° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_install_pose(rm_robot_handle *handle, float x, float y, float z); +/** + * @brief 获取安装方式参数 + * + * @param handle 机械臂控制句柄 + * @param x 旋转角(out),单位 ° + * @param y 俯仰角(out),单位 ° + * @param z 方位角(out),单位 ° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_install_pose(rm_robot_handle *handle, float *x, float *y, float *z); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForcePositionControl 透传力位混合控制补偿 + * + * 针对睿尔曼带一维力和六维力版本的机械臂,用户除了可直接使用示教器调用底层的力位混合控制模块外,还可以将 + * 自定义的轨迹以周期性透传的形式结合底层的力位混合控制算法进行补偿。 + * + * @attention 该功能只适用于一维力传感器和六维力传感器机械臂版本 + * + * 透传效果和周期、轨迹是否平滑有关,周期要求稳定,防止出现较大波动,用户使用该指令时请做好轨迹规划,轨迹规划的 + * 平滑程度决定了机械臂的运行状态。基础系列 WIFI 和网口模式透传周期最快 20ms,USB 和 RS485 模式透传周期最快 10ms。 + * 高速网口的透传周期最快也可到 10ms,不过在使用该高速网口前,需要使用指令打开配置。另外 I 系列有线网口周期最快可达 2ms。 + * + * @{ + */ +/** + * @brief 开启透传力位混合控制补偿模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_start_force_position_move(rm_robot_handle *handle); +/** + * @brief 停止透传力位混合控制补偿模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_force_position_move(rm_robot_handle *handle); +/** + * @brief 透传力位混合补偿-角度方式 + * + * @param handle 机械臂控制句柄 + * @param joint 目标关节角度 + * @param sensor 所使用传感器类型,0-一维力,1-六维力 + * @param mode 模式,0-沿基坐标系,1-沿工具端坐标系 + * @param dir 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + * @param force 力的大小 单位N + * @param follow 是否高跟随 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move_joint(rm_robot_handle *handle,const float *joint,int sensor,int mode,int dir,float force, bool follow); +/** + * @brief 透传力位混合补偿-位姿方式 + * + * @param handle 机械臂控制句柄 + * @param pose 当前坐标系下目标位姿 + * @param sensor 所使用传感器类型,0-一维力,1-六维力 + * @param mode 模式,0-沿基坐标系,1-沿工具端坐标系 + * @param dir 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + * @param force 力的大小 单位N + * @param follow 是否高跟随 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move_pose(rm_robot_handle *handle, rm_pose_t pose,int sensor,int mode,int dir,float force, bool follow); +/** + * @brief 透传力位混合补偿-新参数 + * + * @param handle 机械臂控制句柄 + * @param param 透传力位混合补偿参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move(rm_robot_handle *handle, rm_force_position_move_t param); +/** @} */ // 结束组的定义 + +/** + * @defgroup LiftControl 升降机构 + * + * 升降机构速度开环控制、位置闭环控制及状态获取 + * @{ + */ +/** + * @brief 升降机构速度开环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,-100~100。 + - speed<0:升降机构向下运动 + - speed>0:升降机构向上运动 + - speed=0:升降机构停止运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_lift_speed(rm_robot_handle *handle, int speed); +/** + * @brief 升降机构位置闭环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,1~100 + * @param height 目标高度,单位 mm,范围:0~2600 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待升降机到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为升降机构。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_lift_height(rm_robot_handle *handle, int speed, int height, int block); +/** + * @brief 获取升降机构状态 + * + * @param handle 机械臂控制句柄 + * @param state 当前升降机构状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_lift_state(rm_robot_handle *handle, rm_expand_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup ExpandControl 通用扩展关节 + * + * 扩展关节速度环控制、位置环控制及状态获取 + * @{ + */ +/** + * @brief 扩展关节状态获取 + * + * @param handle 机械臂控制句柄 + * @param state 扩展关节状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_expand_state(rm_robot_handle *handle, rm_expand_state_t *state); +/** + * @brief 扩展关节速度环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,-100~100。 + - speed<0:扩展关节反方向运动 + - speed>0:扩展关节正方向运动 + - speed=0:扩展关节停止运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_expand_speed(rm_robot_handle *handle, int speed); +/** + * @brief 扩展关节位置环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,1~100 + * @param pos 扩展关节角度,单位度 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待升降机到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为扩展关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_expand_pos(rm_robot_handle *handle, int speed, int pos, int block); +/** @} */ // 结束组的定义 + +/** + * @defgroup OnlineProgramming 在线编程 + * + * 包含在线编程文件下发、在线编程文件管理、全局路点管理等相关功能接口。 + * @{ + */ +/** + * @brief 文件下发 + * + * @param handle 机械臂控制句柄 + * @param project 文件下发参数配置结构体 + * @param errline 若运行失败,该参数返回有问题的工程行数,err_line 为 0,则代表校验数据长度不对,err_line 为 -1,则代表无错误 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 文件名称校验失败 + - -5: 文件读取失败 + - -6: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_send_project(rm_robot_handle *handle, rm_send_project_t project, int *errline); +/** + * @brief 规划过程中改变速度系数 + * + * @param handle 机械臂控制句柄 + * @param speed 速度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_plan_speed(rm_robot_handle *handle, int speed); + +/** + * @brief 获取在线编程列表 + * + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param trajectorys 在线编程程序列表 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_program_trajectory_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_program_trajectorys_t *trajectorys); + +/** + * @brief 开始运行指定编号轨迹 + * + * @param handle 机械臂控制句柄 + * @param id 运行指定的ID,1-100,存在轨迹可运行 + * @param speed 1-100,需要运行轨迹的速度,若设置为0,则按照存储的速度运行 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 运行状态已停止但未接收到运行成功,是否在外部停止了轨迹。 + */ +RM_INTERFACE_EXPORT int rm_set_program_id_run(rm_robot_handle *handle, int id, int speed, int block); +/** + * @brief 查询在线编程运行状态 + * + * @param handle 机械臂控制句柄 + * @param run_state 在线编程运行状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_program_run_state(rm_robot_handle *handle, rm_program_run_state_t *run_state); +/** + * @brief 查询流程图运行状态 + * + * @param handle 机械臂控制句柄 + * @param run_state 流程图运行状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_flowchart_program_run_state(rm_robot_handle *handle, rm_flowchart_run_state_t *run_state); +/** + * @brief 删除指定编号编程文件 + * + * @param handle 机械臂控制句柄 + * @param id 指定编程轨迹的编号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_program_trajectory(rm_robot_handle *handle, int id); +/** + * @brief 修改指定编号的编程文件 + * + * @param handle 机械臂控制句柄 + * @param id 指定在线编程轨迹编号 + * @param speed 更新后的规划速度比例 1-100 + * @param name 更新后的文件名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_program_trajectory(rm_robot_handle *handle, int id, int speed, const char* name); +/** + * @brief 设置 IO 默认运行编号 + * + * @param handle 机械臂控制句柄 + * @param id 设置 IO 默认运行的在线编程文件编号,支持 0-100,0 代表取消设置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_default_run_program(rm_robot_handle *handle, int id); +/** + * @brief 获取 IO 默认运行编号 + * + * @param handle 机械臂控制句柄 + * @param id IO 默认运行的在线编程文件编号,支持 0-100,0 代表无默认 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_default_run_program(rm_robot_handle *handle, int *id); +/** + * @brief 新增全局路点 + * + * @param handle 机械臂控制句柄 + * @param waypoint 新增全局路点参数(无需输入新增全局路点时间) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_add_global_waypoint(rm_robot_handle *handle, rm_waypoint_t waypoint); +/** + * @brief 更新全局路点 + * + * @param handle 机械臂控制句柄 + * @param waypoint 更新全局路点参数(无需输入更新全局路点时间) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_global_waypoint(rm_robot_handle *handle, rm_waypoint_t waypoint); +/** + * @brief 删除全局路点 + * + * @param handle 机械臂控制句柄 + * @param point_name 全局路点名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_global_waypoint(rm_robot_handle *handle, const char* point_name); +/** + * @brief 查询指定全局路点 + * + * @param handle 机械臂控制句柄 + * @param name 指定全局路点名称 + * @param point 返回指定的全局路点参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_global_waypoint(rm_robot_handle *handle, const char* name, rm_waypoint_t *point); +/** + * @brief 查询多个全局路点 + * + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param point_list 返回的全局路点列表 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_global_waypoints_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_waypoint_list_t *point_list); +/** @} */ // 结束在线编程组的定义 + +/** + * @defgroup UdpConfig UDP主动上报 + * + * 睿尔曼机械臂提供 UDP 机械臂状态主动上报接口,使用时,需要和机械臂处于同一局域网络下,通过设置主动上报配置接口的目标 IP或和机械臂建立 TCP 连接, + * 机械臂即会主动周期性上报机械臂状态数据,数据周期可配置,默认 5ms。配置正确并开启三线程模式后,通过注册回调函数可接收并处理主动上报数据。 + * @{ + */ +/** + * @brief 设置 UDP 机械臂状态主动上报配置 + * + * @param handle 机械臂控制句柄 + * @param config UDP配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: rm_realtime_push_config_t config参数配置非法。 + */ +RM_INTERFACE_EXPORT int rm_set_realtime_push(rm_robot_handle *handle, rm_realtime_push_config_t config); +/** + * @brief 查询 UDP 机械臂状态主动上报配置 + * + * @param handle 机械臂控制句柄 + * @param config 获取到的UDP机械臂状态主动上报配置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_realtime_push(rm_robot_handle *handle, rm_realtime_push_config_t *config); +/** @} */ // 结束组的定义 + +/** + * @defgroup Electronic_Fence 电子围栏和虚拟墙 + * + * I 系列机械臂具备电子围栏与虚拟墙功能,并提供了针对控制器所保存的电子围栏或虚拟墙几何模型参数的操作接口。 + * 用户可以通过这些接口,实现对电子围栏或虚拟墙的新增、查询、更新和删除操作,在使用中,可以灵活地使用保存在 + * 控制器中的参数配置,需要注意的是,目前控制器支持保存的参数要求不超过10 个。 + * + * 电子围栏 + * 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动 + * 轨迹可能超出电子围栏的界限时,系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。 + * @attention 电子围栏目前仅支持长方体和点面矢量平面这两种形状,并且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境。 + * + * 虚拟墙 + * 虚拟墙功能支持在电流环拖动示教与力控拖动示教两种模式下,对拖动范围进行精确限制。在这两种特定的示教模式下,用户可以借助虚拟墙功能,确保 + * 机械臂的拖动操作不会超出预设的范围。 + * @attention 虚拟墙功能目前支持长方体和球体两种形状,并仅在上述两种示教模式下有效。在其他操作模式下,此功能将自动失效。因此,请确保在正确的操作模式 + * 下使用虚拟墙功能,以充分发挥其限制拖动范围的作用。 + * + * @{ + */ +/** + * @brief 新增几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config 几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: rm_fence_config_t中form设置有误。 + */ +RM_INTERFACE_EXPORT int rm_add_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 更新几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config 几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: rm_fence_config_t中form设置有误。 + */ +RM_INTERFACE_EXPORT int rm_update_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 删除指定几何模型 + * + * @param handle 机械臂控制句柄 + * @param form_name 几何模型名称,不超过 10 个字节,支持字母、数字、下划线 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_electronic_fence_config(rm_robot_handle *handle, const char* form_name); +/** + * @brief 查询所有几何模型名称 + * + * @param handle 机械臂控制句柄 + * @param names 几何模型名称列表,长度为实际存在几何模型数量 + * @param len 几何模型名称列表长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_list_names(rm_robot_handle *handle, rm_fence_names_t *names, int *len); +/** + * @brief 查询指定几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param name 指定几何模型名称 + * @param config 返回几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_electronic_fence_config(rm_robot_handle *handle, const char* name, rm_fence_config_t *config); +/** + * @brief 查询所有几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config_list 几何模型信息列表,长度为实际存在几何模型数量 + * @param len 几何模型信息列表长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_list_infos(rm_robot_handle *handle, rm_fence_config_list_t *config_list, int *len); +/** + * @brief 设置电子围栏使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 电子围栏使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @note 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动轨迹可能超出电子围栏的界限时, + * 系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。需要注意的是,电子围栏目前仅支持长方体和点面矢量平面这两种形状,并 + * 且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境 + */ +RM_INTERFACE_EXPORT int rm_set_electronic_fence_enable(rm_robot_handle *handle, rm_electronic_fence_enable_t state); +/** + * @brief 获取电子围栏使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 电子围栏使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_enable(rm_robot_handle *handle,rm_electronic_fence_enable_t *state); +/** + * @brief 设置当前电子围栏参数配置 + * + * @param handle 机械臂控制句柄 + * @param config 当前电子围栏参数结构体(无需设置电子围栏名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: rm_fence_config_t中form设置有误。 + */ +RM_INTERFACE_EXPORT int rm_set_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 获取当前电子围栏参数 + * + * @param handle 机械臂控制句柄 + * @param config 返回当前电子围栏参数结构体(返回参数中不包含电子围栏名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t *config); +/** + * @brief 设置虚拟墙使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 虚拟墙状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_virtual_wall_enable(rm_robot_handle *handle, rm_electronic_fence_enable_t state); +/** + * @brief 获取虚拟墙使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 虚拟墙状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_virtual_wall_enable(rm_robot_handle *handle,rm_electronic_fence_enable_t *state); +/** + * @brief 设置当前虚拟墙参数 + * + * @param handle 机械臂控制句柄 + * @param config 当前虚拟墙参数(无需设置虚拟墙名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_virtual_wall_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 获取当前虚拟墙参数 + * + * @param handle 机械臂控制句柄 + * @param config 当前虚拟墙参数(返回参数中不包含虚拟墙名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_virtual_wall_config(rm_robot_handle *handle, rm_fence_config_t *config); +/** @} */ // 结束电子围栏组的定义 + +/** + * @defgroup SelfCollision 自碰撞安全检测 + * + * 睿尔曼机械臂支持自碰撞安全检测,自碰撞安全检测使能状态下,可确保在轨迹规划、示教等运动过程中机械臂的各个部分不会相互碰撞。 + * @attention 以上自碰撞安全检测功能目前只在仿真模式下生效,用于进行预演轨迹与轨迹优化。 + * @{ + */ +/** + * @brief 设置自碰撞安全检测使能状态 + * + * @param handle 机械臂控制句柄 + * @param state true代表使能,false代表禁使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_self_collision_enable(rm_robot_handle *handle, bool state); +/** + * @brief 获取自碰撞安全检测使能状态 + * + * @param handle 机械臂控制句柄 + * @param state true代表使能,false代表禁使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_self_collision_enable(rm_robot_handle *handle,bool *state); +/** @} */ // 结束组的定义 + + +/** + * @brief 设置末端生态协议模式 + * @param handle 机械臂控制句柄 + * @param mode 末端生态协议模式 + * 0:禁用协议 + * 9600:开启协议(波特率9600) + * 115200:开启协议(波特率115200) + * 256000:开启协议(波特率256000) + * 460800:开启协议(波特率460800) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_set_rm_plus_mode(rm_robot_handle *handle, int mode); + +/** + * @brief 查询末端生态协议模式 + * @param handle 机械臂控制句柄 + * @param mode 末端生态协议模式 + * 0:禁用协议 + * 9600:开启协议(波特率9600) + * 115200:开启协议(波特率115200) + * 256000:开启协议(波特率256000) + * 460800:开启协议(波特率460800) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_mode(rm_robot_handle *handle, int *mode); + +/** + * @brief 设置触觉传感器模式(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param mode 触觉传感器开关状态 0:关闭触觉传感器 1:打开触觉传感器(返回处理后数据) 2:打开触觉传感器(返回原始数据) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_set_rm_plus_touch(rm_robot_handle *handle, int mode); + +/** + * @brief 查询触觉传感器模式(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param mode 触觉传感器开关状态 0:关闭触觉传感器 1:打开触觉传感器(返回处理后数据) 2:打开触觉传感器(返回原始数据) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_rm_plus_touch(rm_robot_handle *handle, int *mode); + +/** + * @brief 读取末端设备基础信息(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param info 末端设备基础信息 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_base_info(rm_robot_handle *handle, rm_plus_base_info_t *info); + +/** + * @brief 读取末端设备实时信息(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param info 末端设备实时信息 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_state_info(rm_robot_handle *handle, rm_plus_state_info_t *info); + +/******************************************算法接口*******************************************************/ +/** + * @defgroup Algo 算法接口 + * + * 针对睿尔曼机械臂,提供正逆解、各种位姿参数转换等工具接口。 + * @{ + */ +/** + * @brief 查询算法库版本号 + * @return char* 返回版本号 + * @code + * char *version = rm_algo_version(); + * printf("algo version: %s\n", version); + * @endcode + */ +RM_INTERFACE_EXPORT char* rm_algo_version(void); +/** + * @brief 初始化算法依赖数据(不连接机械臂时调用) + * + * @param Mode 机械臂型号 + * @param Type 传感器型号 + */ +RM_INTERFACE_EXPORT void rm_algo_init_sys_data(rm_robot_arm_model_e Mode, rm_force_type_e Type); +/** + * @brief 初始化算法依赖数据(不连接机械臂时调用) + * @details 初始化算法依赖数据,根据给定的DH参数判断机械臂类型,适用于通用型机械臂(RM_MODEL_UNIVERSAL_E)。 + * + * @param sensor_type 传感器型号 + * @param dh DH参数 + * @param dof 自由度 + */ +RM_INTERFACE_EXPORT void rm_algo_init_sys_data_by_dh(rm_force_type_e sensor_type, rm_dh_t dh, int dof); +/** + * @brief 设置算法机械臂自由度 + * @details 通用构型(RM_MODEL_UNIVERSAL_E)设置机器人自由度 + * + * @param dof 机械臂自由度 + */ +RM_INTERFACE_EXPORT void rm_algo_set_robot_dof(int dof); +/** + * @brief 设置安装角度 + * + * @param x X轴安装角度 单位° + * @param y Y轴安装角度 单位° + * @param z z轴安装角度 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_angle(float x, float y, float z); +/** + * @brief 获取安装角度 + * + * @param x X轴安装角度 单位° + * @param y Y轴安装角度 单位° + * @param z z轴安装角度 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_get_angle(float* x, float* y, float* z); +/** + * @brief 设置工作坐标系 + * + * @param coord_work 坐标系数据(无需设置名称) + */ +RM_INTERFACE_EXPORT void rm_algo_set_workframe(const rm_frame_t* const coord_work); +/** + * @brief 获取当前工作坐标系 + * + * @param coord_work 当前工作坐标系(获取到的坐标系参数,不包括坐标系名称) + */ +RM_INTERFACE_EXPORT void rm_algo_get_curr_workframe(rm_frame_t* coord_work); +/** + * @brief 设置工具坐标系 + * + * @param coord_tool 坐标系数据(无需设置名称) + */ +RM_INTERFACE_EXPORT void rm_algo_set_toolframe(const rm_frame_t* const coord_tool); +/** + * @brief 获取算法当前工具坐标系 + * + * @param coord_tool 当前工具坐标系(获取到的坐标系参数,不包括坐标系名称) + */ +RM_INTERFACE_EXPORT void rm_algo_get_curr_toolframe(rm_frame_t* coord_tool); +/** + * @brief 设置算法关节最大限位 + * + * @param joint_limit 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_limit(const float* const joint_limit); +/** + * @brief 获取算法关节最大限位 + * + * @param joint_limit 返回关节最大限位 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_limit(float* joint_limit); +/** + * @brief 设置算法关节最小限位 + * + * @param joint_limit 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_min_limit(const float* const joint_limit); +/** + * @brief 获取算法关节最小限位 + * + * @param joint_limit 返回关节最小限位 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_min_limit(float* joint_limit); +/** + * @brief 设置算法关节最大速度 + * + * @param joint_slim_max RPM + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_speed(const float* const joint_slim_max); +/** + * @brief 获取算法关节最大速度 + * + * @param joint_slim_max 返回关节最大速度 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_speed(float* joint_slim_max); +/** + * @brief 设置算法关节最大加速度 + * + * @param joint_alim_max RPM/s + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_acc(const float* const joint_alim_max); +/** + * @brief 获取算法关节最大加速度 + * + * @param joint_alim_max 返回关节最大加速度 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_acc(float* joint_alim_max); +/** + * @brief 设置逆解求解模式 + * + * @param mode true:遍历模式,冗余参数遍历的求解策略。适于当前位姿跟要求解的位姿差别特别大的应用场景,如MOVJ_P、位姿编辑等,耗时较长 + false:单步模式,自动调整冗余参数的求解策略。适于当前位姿跟要求解的位姿差别特别小、连续周期控制的场景,如笛卡尔空间规划的位姿求解等,耗时短 + */ +RM_INTERFACE_EXPORT void rm_algo_set_redundant_parameter_traversal_mode(bool mode); +/** + * @brief 逆解函数,默认遍历模式,可使用Algo_Set_Redundant_Parameter_Traversal_Mode接口设置逆解求解模式 + * + * @param handle 机械臂控制句柄 + * @param params 逆解输入参数结构体 + * @param q_out 存放输出的关节角度数组 单位° + * @return int 逆解结果 + * - 0: 逆解成功 + * - 1: 逆解失败 + * - -1: 上一时刻关节角度输入为空或超关节限位 + * - -2: 目标位姿四元数不合法 + * @attention 机械臂已连接时,可直接调用该接口进行计算,计算使用的参数均为机械臂当前的参数; + * 未连接机械臂时,需首先调用初始化算法依赖数据接口,并按照实际需求设置使用的坐标系、安装方式及关节速度位置等限制 + *(不设置则按照出厂默认的参数进行计算),此时机械臂控制句柄设置为NULL即可 + */ +RM_INTERFACE_EXPORT int rm_algo_inverse_kinematics(rm_robot_handle *handle, rm_inverse_kinematics_params_t params, float *q_out); + +/** + * @brief 计算逆运动学全解(当前仅支持六自由度机器人) + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param params 逆解输入参数结构体 + * @return rm_inverse_kinematics_all_solve_t 逆解的全解结构体 +*/ +RM_INTERFACE_EXPORT rm_inverse_kinematics_all_solve_t rm_algo_inverse_kinematics_all(rm_robot_handle *handle, rm_inverse_kinematics_params_t params); + +/** + * @brief 从多解中选取最优解(当前仅支持六自由度机器人) + * @param weight 权重,建议默认值为{1,1,1,1,1,1} + * @param params 待选解的全解结构体 + * @return int 最优解索引,选解结果为ik_solve.q_solve[i],如果没有合适的解返回-1(比如求出8组解,但是8组都有关节角度超限位,那么就返回-1) +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_select_ik_solve(float *weight, rm_inverse_kinematics_all_solve_t params); + + +/** + * @brief 检查逆解结果是否超出关节限位(当前仅支持六自由度机器人) + * @param q_solve 选解,单位:° + * @return int 0:未超限位,1~dof: 第i个关节超限位 -1:当前机器人非六自由度,当前仅支持六自由度机器人 +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_check_joint_position_limit(const float* const q_solve); + +/** + * @brief 检查逆解结果是否超速(当前仅支持六自由度机器人) + * @param dt 两帧数据之间的时间间隔,即控制周期,单位sec + * @param q_ref 参考关节角度或者第一帧数据角度,单位:° + * @param q_solve 求解结果,即下一帧要发送的角度 + * @return int 0:表示未超限 i:表示关节i超限,优先报序号小的关节 -1:当前机器人非六自由度,当前仅支持六自由度机器人 +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_check_joint_velocity_limit(float dt, const float* const q_ref, const float* const q_solve); + + +/** + * @brief 根据参考位形计算臂角大小(仅支持RM75) + * @param q_ref 当前参考位形的关节角度,单位° + * @param arm_angle 计算结果,当前参考位形对应的臂角大小,单位° + * @return int + * 0: 求解成功 + * -1: 求解失败,或机型非RM75 + * -2: q_ref 输入参数非法 + */ +RM_INTERFACE_EXPORT int rm_algo_calculate_arm_angle_from_config_rm75(float *q_ref, float *arm_angle); + +/** + * @brief 臂角法求解RM75逆运动学 + * @param params rm_inverse_kinematics_params_t,逆解参数结构体 + * @param arm_angle 指定轴角大小,单位:° + * @param q_solve 求解结果,单位:° + * @return int + * 0: 求解成功 + * -1: 求解失败 + * -2: 求解结果超出限位 + * -3: 机型非RM75 + */ +RM_INTERFACE_EXPORT int rm_algo_inverse_kinematics_rm75_for_arm_angle(rm_inverse_kinematics_params_t params, float arm_angle, float *q_solve); + +/** + * @brief 通过分析雅可比矩阵最小奇异值, 判断机器人是否处于奇异状态 + * @param q 要判断的关节角度(机械零位描述),单位:° + * @param 最小奇异值阈值,若传NULL,则使用内部默认值,默认值为0.01(该值在0-1之间) + * @return 0:在当前阈值条件下正常 + * -1:表示在当前阈值条件下判断为奇异区 + * -2:表示计算失败 + */ +RM_INTERFACE_EXPORT int rm_algo_universal_singularity_analyse(const float* const q, float singluar_value_limit); +/** + * @brief 设置自定义阈值(仅适用于解析法分析机器人奇异状态) + * @param limit_qe 肘部奇异区域范围设置(即J3接近0的范围),unit: °,default:about 10deg + * @param limit_qw 腕部奇异区域范围设置(即J5接近0的范围),unit: °,default:about 10deg + * @param limit_d 肩部奇异区域范围设置(即腕部中心点距离奇异平面的距离), unit: m, default: 0.05 +*/ +RM_INTERFACE_EXPORT void rm_algo_kin_set_singularity_thresholds(float limit_qe_algo, float limit_qw_algo, float limit_d_algo); +/** + * @brief 获取自定义阈值(仅适用于解析法分析机器人奇异状态) + * + * @param limit_qe 肘部奇异区域范围获取(即J3接近0的范围), unit: °, default: about 10deg + * @param limit_qw 腕部奇异区域范围获取(即J5接近0的范围), unit: °, default: about 10deg + * @param limit_d 肩部奇异区域范围获取(即腕部中心点距离奇异平面的距离), unit: m, default: 0.05 + */ +RM_INTERFACE_EXPORT void rm_algo_kin_get_singularity_thresholds(float* limit_qe_algo, float* limit_qw_algo, float* limit_d_algo); + +/** + * @brief 恢复初始阈值(仅适用于解析法分析机器人奇异状态),阈值初始化为:limit_qe=10deg,limit_qw=10deg,limit_d = 0.05m +*/ +RM_INTERFACE_EXPORT void rm_algo_kin_singularity_thresholds_init(); +/** + * @brief 解析法判断机器人是否处于奇异位形(仅支持六自由度) + * @param q 要判断的关节角度,单位:° + * @param distance 输出参数,返回腕部中心点到肩部奇异平面的距离,该值越接近0说明越接近肩部奇异,单位m,不需要时可传NULL + * @return 0表正常,-1表肩部奇异,-2表肘部奇异,-3表腕部奇异,-4表仅支持6自由度机械臂 +*/ +RM_INTERFACE_EXPORT int rm_algo_kin_robot_singularity_analyse(const float* const q, float *distance); +/** + * @brief 设置工具包络球参数 + * @param toolSphere_i 工具包络球编号 (0~4) + * @param data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + */ +RM_INTERFACE_EXPORT void rm_algo_set_tool_envelope(const int toolSphere_i, rm_tool_sphere_t data); + +/** + * @brief 获取工具包络球参数 + * @param toolSphere_i 工具rm_get_tool_voltage包络球编号 (0~4) + * @param data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + */ +RM_INTERFACE_EXPORT void rm_algo_get_tool_envelope(const int toolSphere_i, rm_tool_sphere_t *data); +/** + * @brief 自碰撞检测 + * @param joint 要判断的关节角度,单位:° + * @return int + * 0: 无碰撞 + * 1: 发生碰撞,超出关节限位将被认为发生碰撞 + */ +RM_INTERFACE_EXPORT int rm_algo_safety_robot_self_collision_detection(float *joint); +/** + * @brief 正解算法接口 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param joint 关节角度,单位:° + * + * @return rm_pose_t 目标位姿 + * @attention 机械臂已连接时,可直接调用该接口进行计算,计算使用的参数均为机械臂当前的参数; + * 未连接机械臂时,需首先调用初始化算法依赖数据接口,并按照实际需求设置使用的坐标系、安装方式及关节速度位置等限制 + *(不设置则按照出厂默认的参数进行计算),此时机械臂控制句柄设置为NULL即可 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_forward_kinematics(rm_robot_handle *handle,const float* const joint); +/** + * @brief 欧拉角转四元数 + * + * @param eu 欧拉角,单位:rad + * @return rm_quat_t 四元数 + */ +RM_INTERFACE_EXPORT rm_quat_t rm_algo_euler2quaternion(rm_euler_t eu); +/** + * @brief 四元数转欧拉角 + * + * @param qua 四元数 + * @return rm_euler_t 欧拉角 + */ +RM_INTERFACE_EXPORT rm_euler_t rm_algo_quaternion2euler(rm_quat_t qua); +/** + * @brief 欧拉角转旋转矩阵 + * + * @param state 欧拉角,单位:rad + * @return rm_matrix_t 旋转矩阵 + */ +RM_INTERFACE_EXPORT rm_matrix_t rm_algo_euler2matrix(rm_euler_t state); +/** + * @brief 位姿转旋转矩阵 + * + * @param state 位姿 + * @return rm_matrix_t 旋转矩阵 + */ +RM_INTERFACE_EXPORT rm_matrix_t rm_algo_pos2matrix(rm_pose_t state); +/** + * @brief 旋转矩阵转位姿 + * + * @param matrix 旋转矩阵 + * @return rm_pose_t 位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_matrix2pos(rm_matrix_t matrix); +/** + * @brief 基坐标系转工作坐标系 + * + * @param matrix 工作坐标系在基坐标系下的矩阵 + * @param state 工具端坐标在基坐标系下位姿 + * @return rm_pose_t 基坐标系在工作坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_base2workframe(rm_matrix_t matrix, rm_pose_t state); +/** + * @brief 工作坐标系转基坐标系 + * + * @param matrix 工作坐标系在基坐标系下的矩阵 + * @param state 工具端坐标在工作坐标系下位姿 + * @return rm_pose_t 工作坐标系在基坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_workframe2base(rm_matrix_t matrix, rm_pose_t state); +/** + * @brief 计算环绕运动位姿 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param curr_joint 当前关节角度 单位° + * @param rotate_axis 旋转轴: 1:x轴, 2:y轴, 3:z轴 + * @param rotate_angle 旋转角度: 旋转角度, 单位(度) + * @param choose_axis 指定计算时使用的坐标系 + * @return rm_pose_t 计算位姿结果 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_rotate_move(rm_robot_handle *handle,const float* const curr_joint, int rotate_axis, float rotate_angle, rm_pose_t choose_axis); +/** + * @brief 计算沿工具坐标系运动位姿 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param curr_joint 当前关节角度,单位:度 + * @param move_lengthx 沿X轴移动长度,单位:米 + * @param move_lengthy 沿Y轴移动长度,单位:米 + * @param move_lengthz 沿Z轴移动长度,单位:米 + * @return rm_pose_t 工作坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_cartesian_tool(rm_robot_handle *handle,const float* const curr_joint, float move_lengthx, + float move_lengthy, float move_lengthz); +/** + * @brief 计算Pos和Rot沿某坐标系有一定的位移和旋转角度后,所得到的位姿数据 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param poseCurrent 当前时刻位姿(欧拉角形式) + * @param deltaPosAndRot 移动及旋转数组,位置移动(单位:m),旋转(单位:度) + * @param frameMode 坐标系模式选择 0:Work(work即可任意设置坐标系),1:Tool + * @return rm_pose_t 平移旋转后的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_pose_move(rm_robot_handle *handle,rm_pose_t poseCurrent, const float *deltaPosAndRot, int frameMode); +/** + * @brief 末端位姿转成工具位姿 + * + * @param handle 机械臂控制句柄 + * @param eu_end 基于世界坐标系和默认工具坐标系的末端位姿 + * @return rm_pose_t 基于工作坐标系和工具坐标系的末端位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_end2tool(rm_robot_handle *handle,rm_pose_t eu_end); +/** + * @brief 工具位姿转末端位姿 + * + * @param handle 机械臂控制句柄 + * @param eu_tool 基于工作坐标系和工具坐标系的末端位姿 + * @return rm_pose_t 基于世界坐标系和默认工具坐标系的末端位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_tool2end(rm_robot_handle *handle,rm_pose_t eu_tool); +/** + * @brief 获取DH参数 + * + * @return rm_DH_t DH参数 + */ +RM_INTERFACE_EXPORT rm_dh_t rm_algo_get_dh(); +/** + * @brief 设置DH参数 + * + * @param dh DH参数 + */ +RM_INTERFACE_EXPORT void rm_algo_set_dh(rm_dh_t dh); + +/** @} */ // 结束算法组的定义 + +/*********************************************四代控制器新增接口*******************************************************/ + +/** + * @brief 查询轨迹列表 + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param list 轨迹列表 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_trajectory_file_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_trajectory_list_t *trajectory_list); +/** + * @brief 开始运行指定轨迹 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_run_trajectory(rm_robot_handle *handle, const char *trajectory_name); +/** + * @brief 删除指定轨迹 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_delete_trajectory_file(rm_robot_handle *handle, const char *trajectory_name); +/** + * @brief 保存轨迹到控制器 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_save_trajectory_file(rm_robot_handle *handle, const char *trajectory_name); + +/** + * @brief 设置机械臂急停状态 + * @param handle 机械臂控制句柄 + * @param state 急停状态,true:急停,false:恢复 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_arm_emergency_stop(rm_robot_handle *handle, bool state); +/** + * @brief 新增Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_add_modbus_tcp_master(rm_robot_handle *handle, rm_modbus_tcp_master_info_t master); +/** + * @brief 修改Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @param master 要修改的Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_update_modbus_tcp_master(rm_robot_handle *handle, const char *master_name, rm_modbus_tcp_master_info_t master); +/** + * @brief 删除Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_delete_modbus_tcp_master(rm_robot_handle *handle, const char *master_name); +/** + * @brief 查询Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @param master Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_modbus_tcp_master(rm_robot_handle *handle, const char *master_name, rm_modbus_tcp_master_info_t *master); +/** + * @brief 查询TCP主站列表 + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param list TCP主站列表 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_modbus_tcp_master_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_modbus_tcp_master_list_t *list); +/** + * @brief 设置控制器RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param mode 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + * @param baudrate 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_controller_rs485_mode(rm_robot_handle *handle, int mode, int baudrate); +/** + * @brief 查询控制器RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param controller_rs485_mode 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + * @param baudrate 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_controller_rs485_mode_v4(rm_robot_handle *handle, int *controller_rs485_mode, int *baudrate); +/** + * @brief 设置工具端RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param mode 通讯端口,0-设置工具端RS485端口为RTU主站,1-设置工具端RS485端口为灵巧手模式,2-设置工具端RS485端口为夹爪模式。 + * @param baudrate 波特率(当前支持9600,115200,460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_tool_rs485_mode(rm_robot_handle *handle, int mode, int baudrate); +/** + * @brief 查询工具端RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param tool_rs485_mode 0-代表modbus-RTU主站模式,1-代表灵巧手模式,2-代表夹爪模式。 + * @param baudrate 波特率(当前支持9600,115200,460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_tool_rs485_mode_v4(rm_robot_handle *handle, int *tool_rs485_mode, int *baudrate); +/** + * @brief Modbus RTU协议读线圈 + * @param handle 机械臂控制句柄 + * @param param 读线圈参数 + * @param data 读线圈数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_coils(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议写线圈 + * @param handle 机械臂控制句柄 + * @param param 写线圈参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_rtu_coils(rm_robot_handle *handle, rm_modbus_rtu_write_params_t param); +/** + * @brief Modbus RTU协议读离散量输入 + * @param handle 机械臂控制句柄 + * @param param 读离散输入参数 + * @param data 读离散输入数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_input_status(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议读保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 读保持寄存器参数 + * @param data 读保持寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_holding_registers(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议写保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 写保持寄存器参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_rtu_registers(rm_robot_handle *handle, rm_modbus_rtu_write_params_t param); +/** + * @brief Modbus RTU协议读输入寄存器 + * @param handle 机械臂控制句柄 + * @param param 读输入寄存器参数 + * @param data 读输入寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_input_registers(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus TCP协议读线圈 + * @param handle 机械臂控制句柄 + * @param param 读线圈参数 + * @param data 读线圈数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_coils(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议写线圈 + * @param handle 机械臂控制句柄 + * @param param 写线圈参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_tcp_coils(rm_robot_handle *handle, rm_modbus_tcp_write_params_t param); +/** + * @brief Modbus TCP协议读离散量输入 + * @param handle 机械臂控制句柄 + * @param param 读离散输入参数 + * @param data 读离散输入数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_input_status(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议读保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 读保持寄存器参数 + * @param data 读保持寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_holding_registers(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议写保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 写保持寄存器参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_tcp_registers(rm_robot_handle *handle, rm_modbus_tcp_write_params_t param); +/** + * @brief Modbus TCP协议读输入寄存器 + * @param handle 机械臂控制句柄 + * @param param 读输入寄存器参数 + * @param data 读输入寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_input_registers(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/include/rm_interface_global.h b/include/rm_interface_global.h new file mode 100644 index 0000000..f771b85 --- /dev/null +++ b/include/rm_interface_global.h @@ -0,0 +1,16 @@ +#ifndef RM_INTERFACE_GLOBAL_H +#define RM_INTERFACE_GLOBAL_H + +#ifdef __linux +#define RM_INTERFACE_EXPORT +#endif + +#if _WIN32 +#if defined(RM_INTERFACE_LIBRARY) +# define RM_INTERFACE_EXPORT __declspec(dllexport) +#else +# define RM_INTERFACE_EXPORT __declspec(dllexport) +#endif +#endif + +#endif // RM_INTERFACE_GLOBAL_H diff --git a/include/rm_service.h b/include/rm_service.h new file mode 100644 index 0000000..6290b0a --- /dev/null +++ b/include/rm_service.h @@ -0,0 +1,4553 @@ +#ifndef RM_SERVICE_H +#define RM_SERVICE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "rm_interface.h" +#include "rm_interface_global.h" + +#ifdef __cplusplus +} + +class RM_Service { +public: +/** + * @defgroup Init_Class 初始化及连接 + * + * 此模块为API及机械臂初始化相关接口,包含API版本号查询、API初始化、连接/断开机械臂、日志设置、 + * 机械臂仿真/真实模式设置、机械臂信息获取、运动到位信息及机械臂实时状态信息回调函数注册等 + * @{ + */ +/** + * @brief 查询sdk版本号 + * + * @code + * char *version = rm_api_version(); + * printf("api version: %s\n", version); + * @endcode + * @return char* 返回版本号 + */ +RM_INTERFACE_EXPORT char* rm_api_version(void); +/** + * @brief 初始化线程模式 + * + * @param mode RM_SINGLE_MODE_E:单线程模式,单线程非阻塞等待数据返回; + * RM_DUAL_MODE_E:双线程模式,增加接收线程监测队列中的数据; + * RM_TRIPLE_MODE_E:三线程模式,在双线程模式基础上增加线程监测UDP接口数据; + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 创建线程失败。查看日志以获取具体错误 + * @see rm_create_robot_arm + */ +RM_INTERFACE_EXPORT int rm_init(rm_thread_mode_e mode); + +/** + * @brief 关闭所有连接,销毁所有线程 + * + * @return int 函数执行的状态码。 + - 0: 成功。 + */ +RM_INTERFACE_EXPORT int rm_destroy(void); + +/** + * @brief 日志打印配置 + * + * @param LogCallback 日志打印回调函数 + * @param level 日志打印等级,0:debug级别,1:info级别,2:warn:级别,3:error级别 + */ + RM_INTERFACE_EXPORT void rm_set_log_call_back(void (*LogCallback)(const char* message, va_list args),int level); + +/** + * @brief 保存日志到文件 + * + * @param path 日志保存文件路径 + */ +RM_INTERFACE_EXPORT void rm_set_log_save(const char* path); + +/** + * @brief 设置全局超时时间 + * + * @param timeout 接收控制器返回指令超时时间,多数接口默认超时时间为500ms,单位ms + */ +RM_INTERFACE_EXPORT void rm_set_timeout(int timeout); + +/** + * @brief 创建一个机械臂,用于实现对该机械臂的控制 + * + * @param ip 机械臂的ip地址 + * @param port 机械臂的端口号 + * @return rm_robot_handle* 创建成功后,返回机械臂控制句柄,达到最大连接数5或者连接失败返回空 + * @see rm_init + */ +RM_INTERFACE_EXPORT rm_robot_handle *rm_create_robot_arm(const char *ip,int port); + +/** + * @brief 根据句柄删除机械臂 + * + * @param handle 需要删除的机械臂句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + */ +RM_INTERFACE_EXPORT int rm_delete_robot_arm(rm_robot_handle *handle); +/** + * @brief 机械臂仿真/真实模式设置 + * + * @param handle 机械臂控制句柄 + * @param mode 模式 0:仿真 1:真实 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_run_mode(rm_robot_handle *handle, int mode); +/** + * @brief 机械臂仿真/真实模式获取 + * + * @param handle 机械臂控制句柄 + * @param mode 模式 0:仿真 1:真实 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_run_mode(rm_robot_handle *handle,int *mode); +/** + * @brief 获取机械臂基本信息 + * + * @param handle 机械臂控制句柄 + * @param robot_info 机械臂基本信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 未找到对应句柄,句柄为空或已被删除。 + - -2: 获取到的机械臂基本信息非法,检查句柄是否已被删除。 + */ +RM_INTERFACE_EXPORT int rm_get_robot_info(rm_robot_handle *handle, rm_robot_info_t *robot_info); +/** + * @brief 机械臂事件回调注册 + * + * @param handle 机械臂控制句柄 + * @param event_callback 机械臂事件回调函数 + */ +RM_INTERFACE_EXPORT void rm_get_arm_event_call_back(rm_event_callback_ptr event_callback); +/** + * @brief UDP机械臂状态主动上报信息回调注册 + * + * @param handle 机械臂控制句柄 + * @param realtime_callback 机械臂状态信息回调函数 + */ +RM_INTERFACE_EXPORT void rm_realtime_arm_state_call_back(rm_realtime_arm_state_callback_ptr realtime_callback); +/** @} */ // 结束初始化组的定义 +/** + * @defgroup Joint_Config 关节配置 + * + * 对机械臂的关节参数进行设置,如果关节发生错误,则无法修改关节参数,必须先清除关节错误代码。另外设置关节之前, + * 必须先将关节掉使能,否则会设置不成功。 + * 关节所有参数在修改完成后,会自动保存到关节 Flash,立即生效,之后关节处于掉使能状态,修改完参数后必须 + * 发送指令控制关节上使能。 + * @attention 睿尔曼机械臂在出厂前所有参数都已经配置到最佳状态,一般不建议用户修改关节的底层参数。若用户确需修改,首先 + * 应使机械臂处于非使能状态,然后再发送修改参数指令,参数设置成功后,发送关节恢复使能指令。需要注意的是,关节恢复 + * 使能时,用户需要保证关节处于静止状态,以免上使能过程中关节发生报错。关节正常上使能后,用户方可控制关节运动。 + * @{ + */ +/** + * @brief 设置关节最大速度 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_speed 关节最大速度,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_speed(rm_robot_handle *handle,int joint_num,float max_speed); +/** + * @brief 设置关节最大加速度 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_acc 关节最大加速度,单位:°/s² + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_acc(rm_robot_handle *handle,int joint_num,float max_acc); +/** + * @brief 设置关节最小限位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param min_pos 关节最小位置,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_min_pos(rm_robot_handle *handle,int joint_num,float min_pos); +/** + * @brief 设置关节最大限位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_pos 关节最大位置,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_max_pos(rm_robot_handle *handle,int joint_num,float max_pos); +/** + * @brief 设置关节最大速度(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_speed 关节最大速度,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_speed(rm_robot_handle *handle,int joint_num,float max_speed); +/** + * @brief 设置关节最大加速度(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_acc 关节最大加速度,单位:°/s² + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_acc(rm_robot_handle *handle,int joint_num,float max_acc); +/** + * @brief 设置关节最小限位(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param min_pos 关节最小位置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_min_pos(rm_robot_handle *handle,int joint_num,float min_pos); +/** + * @brief 设置关节最大限位(驱动器) + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param max_pos 关节最大位置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_drive_max_pos(rm_robot_handle *handle,int joint_num,float max_pos); +/** + * @brief 设置关节使能状态 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @param en_state 1:上使能 0:掉使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_en_state(rm_robot_handle *handle,int joint_num,int en_state); +/** + * @brief 设置关节零位 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_zero_pos(rm_robot_handle *handle,int joint_num); +/** + * @brief 清除关节错误代码 + * + * @param handle 机械臂句柄 + * @param joint_num 关节序号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_clear_err(rm_robot_handle *handle,int joint_num); +/** + * @brief 一键设置关节限位 + * + * @param handle 机械臂句柄 + * @param limit_mode 1-正式模式,各关节限位为规格参数中的软限位和硬件限位 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_auto_set_joint_limit(rm_robot_handle *handle,int limit_mode); +/** + * @brief 查询关节最大速度 + * + * @param handle 机械臂句柄 + * @param max_speed 关节1~7转速数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_speed(rm_robot_handle *handle,float *max_speed); +/** + * @brief 查询关节最大加速度 + * + * @param handle 机械臂句柄 + * @param max_acc 关节1~7加速度数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_acc(rm_robot_handle *handle,float *max_acc); +/** + * @brief 查询关节最小限位 + * + * @param handle 机械臂句柄 + * @param min_pos 关节1~7最小位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_min_pos(rm_robot_handle *handle,float *min_pos); +/** + * @brief 查询关节最大限位 + * + * @param handle 机械臂句柄 + * @param max_pos 关节1~7最大位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_max_pos(rm_robot_handle *handle,float *max_pos); +/** + * @brief 查询关节(驱动器)最大速度 + * + * @param handle 机械臂句柄 + * @param max_speed 关节1~7转速数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_speed(rm_robot_handle *handle,float *max_speed); +/** + * @brief 查询关节(驱动器)最大加速度 + * + * @param handle 机械臂句柄 + * @param max_acc 关节1~7加速度数组,单位:°/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_acc(rm_robot_handle *handle,float *max_acc); +/** + * @brief 查询关节(驱动器)最小限位 + * + * @param handle 机械臂句柄 + * @param min_pos 关节1~7最小位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_min_pos(rm_robot_handle *handle,float *min_pos); +/** + * @brief 查询关节(驱动器)最大限位 + * + * @param handle 机械臂句柄 + * @param max_pos 关节1~7最大位置数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_drive_max_pos(rm_robot_handle *handle,float *max_pos); +/** + * @brief 查询关节使能状态 + * + * @param handle 机械臂句柄 + * @param en_state 关节1~7使能状态数组,1-使能状态,0-掉使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_en_state(rm_robot_handle *handle,uint8_t *en_state); +/** + * @brief 查询关节错误代码 + * + * @param handle 机械臂句柄 + * @param err_flag 反馈关节错误代码,错误码请参见 \ref robotic_error + * @param brake_state 反馈关节抱闸状态,1 代表抱闸未打开,0 代表抱闸已打开 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_err_flag(rm_robot_handle *handle,uint16_t *err_flag,uint16_t *brake_state); +/** @} */ // 结束关节配置组的定义 + +/** + * @defgroup ArmTipVelocityParameters 机械臂末端参数配置 + * + * 机械臂末端运动参数设置及获取 + * @{ + */ +/** + * @brief 设置机械臂末端最大线速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大线速度,单位m/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_line_speed(rm_robot_handle *handle,float speed); +/** + * @brief 设置机械臂末端最大线加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大线加速度,单位m/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_line_acc(rm_robot_handle *handle,float acc); +/** + * @brief 设置机械臂末端最大角速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大角速度,单位rad/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_angular_speed(rm_robot_handle *handle,float speed); +/** + * @brief 设置机械臂末端最大角加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大角加速度,单位rad/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_max_angular_acc(rm_robot_handle *handle,float acc); +/** + * @brief 设置机械臂末端参数为默认值 + * + * @param handle 机械臂句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_tcp_init(rm_robot_handle *handle); +/** + * @brief 设置机械臂动力学碰撞检测等级 + * + * @param handle 机械臂句柄 + * @param collision_stage 等级:0~8,0-无碰撞,8-碰撞最灵敏 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_collision_state(rm_robot_handle *handle,int collision_stage); +/** + * @brief 查询碰撞防护等级 + * + * @param handle 机械臂句柄 + * @param collision_stage 等级,范围:0~8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_collision_stage(rm_robot_handle *handle,int *collision_stage); +/** + * @brief 获取机械臂末端最大线速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大线速度,单位m/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_line_speed(rm_robot_handle *handle, float *speed); +/** + * @brief 获取机械臂末端最大线加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大线加速度,单位m/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_line_acc(rm_robot_handle *handle, float *acc); +/** + * @brief 获取机械臂末端最大角速度 + * + * @param handle 机械臂句柄 + * @param speed 末端最大角速度,单位rad/s + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_angular_speed(rm_robot_handle *handle, float *speed); +/** + * @brief 获取机械臂末端最大角加速度 + * + * @param handle 机械臂句柄 + * @param acc 末端最大角加速度,单位rad/s^2 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_max_angular_acc(rm_robot_handle *handle, float *acc); +/** + * @brief 设置DH参数 + * + * @param handle 机械臂控制句柄 + * @param dh DH参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DH_data(rm_robot_handle *handle, rm_dh_t dh); +/** + * @brief 获取DH参数 + * + * @param handle 机械臂控制句柄 + * @param dh DH参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_DH_data(rm_robot_handle *handle, rm_dh_t *dh); +/** + * @brief 恢复机械臂默认 DH 参数 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DH_data_default(rm_robot_handle *handle); +/** @} */ // 结束组的定义 +/** + * @defgroup ToolCoordinateConfig 工具坐标系配置 + * + * 工具坐标系标定、切换、删除、修改、查询及工具包络参数等管理 + * @{ + */ +/** + * @brief 六点法自动设置工具坐标系 标记点位 + * + * @param handle 机械臂控制句柄 + * @param point_num 1~6代表6个标定点 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_auto_tool_frame(rm_robot_handle *handle,int point_num); +/** + * @brief 六点法自动设置工具坐标系 提交 + * + * @param handle 机械臂控制句柄 + * @param name 工具坐标系名称,不能超过十个字节。 + * @param payload 新工具执行末端负载重量 单位kg + * @param x 新工具执行末端负载位置 位置x 单位m + * @param y 新工具执行末端负载位置 位置y 单位m + * @param z 新工具执行末端负载位置 位置z 单位m + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_generate_auto_tool_frame(rm_robot_handle *handle, const char *name,float payload,float x,float y,float z); +/** + * @brief 手动设置工具坐标系 + * + * @param handle 机械臂句柄 + * @param frame 新工具坐标系参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_manual_tool_frame(rm_robot_handle *handle, rm_frame_t frame); +/** + * @brief 切换当前工具坐标系 + * + * @param handle 机械臂句柄 + * @param tool_name 目标工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_change_tool_frame(rm_robot_handle *handle, const char* tool_name); +/** + * @brief 删除指定工具坐标系 + * + * @param handle 机械臂句柄 + * @param tool_name 要删除的工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_tool_frame(rm_robot_handle *handle, const char* tool_name); +/** + * @brief 修改指定工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame 要修改的工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_tool_frame(rm_robot_handle *handle, rm_frame_t frame); +/** + * @brief 获取所有工作坐标系名称 + * + * @param handle 机械臂控制句柄 + * @param frame_names 返回的工作坐标系名称字符数组 + * @param len 返回的工作坐标系名称长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_total_tool_frame(rm_robot_handle *handle, rm_frame_name_t *frame_names, int *len); +/** + * @brief 获取指定工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param name 指定的工具坐标系名称 + * @param frame 返回的工具参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_tool_frame(rm_robot_handle *handle, const char *name, rm_frame_t *frame); +/** + * @brief 获取当前工具坐标系 + * + * @param handle 机械臂控制句柄 + * @param tool_frame 返回的坐标系 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_tool_frame(rm_robot_handle *handle, rm_frame_t *tool_frame); +/** + * @brief 设置工具坐标系的包络参数 + * + * @param handle 机械臂控制句柄 + * @param envelope 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_envelope(rm_robot_handle *handle, rm_envelope_balls_list_t envelope); +/** + * @brief 获取工具坐标系的包络参数 + * + * @param handle 机械臂控制句柄 + * @param tool_name 控制器中已存在的工具坐标系名称 + * @param envelope 包络参数列表,每个工具最多支持 5 个包络球,可以没有包络 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回获取失败,检查工具坐标系是否存在。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_envelope(rm_robot_handle *handle, const char* tool_name, rm_envelope_balls_list_t *envelope); +/** @} */ // 结束组的定义 + +/** + * @defgroup WorkCoordinateConfig 工作坐标系配置 + * + * 工作坐标系标定、切换、删除、修改、查询等管理 + * @{ + */ +/** + * @brief 三点法自动设置工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param workname 工作坐标系名称,不能超过十个字节。 + * @param point_num 1~3代表3个标定点,依次为原点、X轴一点、Y轴一点,4代表生成坐标系。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_auto_work_frame(rm_robot_handle *handle,const char *workname, int point_num); +/** + * @brief 手动设置工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 工作坐标系名称,不能超过十个字节。 + * @param pose 新工作坐标系相对于基坐标系的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_manual_work_frame(rm_robot_handle *handle, const char* work_name, rm_pose_t pose); +/** + * @brief 切换当前工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 目标工作坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_change_work_frame(rm_robot_handle *handle, const char* work_name); +/** + * @brief 删除指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 要删除的工具坐标系名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_work_frame(rm_robot_handle *handle, const char* work_name); +/** + * @brief 修改指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_name 指定工具坐标系名称 + * @param pose 更新工作坐标系相对于基坐标系的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_work_frame(rm_robot_handle *handle, const char* work_name, rm_pose_t pose); +/** + * @brief 获取所有工作坐标系名称 + * + * @param handle 机械臂控制句柄 + * @param frame_names 返回的工作坐标系名称字符数组 + * @param len 返回的工作坐标系名称长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_total_work_frame(rm_robot_handle *handle, rm_frame_name_t *frame_names, int *len); +/** + * @brief 获取指定工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param name 指定的工作坐标系名称 + * @param pose 获取到的位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_work_frame(rm_robot_handle *handle, const char *name, rm_pose_t *pose); +/** + * @brief 获取当前工作坐标系 + * + * @param handle 机械臂控制句柄 + * @param work_frame 返回的坐标系 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_work_frame(rm_robot_handle *handle, rm_frame_t *work_frame); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmState 机械臂状态查询 + * + * 机械臂当前状态、关节温度、电流、电压查询 + * @{ + */ +/** + * @brief 获取机械臂当前状态 + * + * @param handle 机械臂控制句柄 + * @param state 机械臂当前状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_arm_state(rm_robot_handle *handle,rm_current_arm_state_t *state); +/** + * @brief 获取关节当前温度 + * + * @param handle 机械臂控制句柄 + * @param temperature 关节1~7温度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_temperature(rm_robot_handle *handle, float *temperature); +/** + * @brief 获取关节当前电流 + * + * @param handle 机械臂控制句柄 + * @param current 关节1~7电流数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_current(rm_robot_handle *handle, float *current); +/** + * @brief 获取关节当前电压 + * + * @param handle 机械臂控制句柄 + * @param voltage 关节1~7电压数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_current_joint_voltage(rm_robot_handle *handle, float *voltage); +/** + * @brief 获取当前关节角度 + * + * @param handle 机械臂控制句柄 + * @param joint 当前7个关节的角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_degree(rm_robot_handle *handle, float *joint); +/** + * @brief 获取机械臂所有状态信息 + * + * @param handle 机械臂控制句柄 + * @param state 存储机械臂信息的结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_all_state(rm_robot_handle *handle, rm_arm_all_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup InitPose 初始位置设置 + * + * 记录机械臂初始位置 + * @{ + */ +/** + * @brief 设置机械臂的初始位置角度 + * + * @param handle 机械臂控制句柄 + * @param joint 机械臂初始位置关节角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_init_pose(rm_robot_handle *handle, float *joint); +/** + * @brief 获取机械臂初始位置角度 + * + * @param handle 机械臂控制句柄 + * @param joint 机械臂初始位置关节角度数组 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_init_pose(rm_robot_handle *handle, float *joint); +/** @} */ // 结束组的定义 + +/** + * @defgroup MovePlan 机械臂轨迹指令类 + * + * 关节运动、笛卡尔空间运动以及角度及位姿透传 + * @{ + */ +/** + * @brief 关节空间运动 + * + * @param handle 机械臂控制句柄 + * @param joint 目标关节1~7角度数组 + * @param v 速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movej(rm_robot_handle *handle, const float *joint, int v, int r,int trajectory_connect,int block); +/** + * @brief 笛卡尔空间直线运动 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movel(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 笛卡尔空间直线偏移运动(四代控制器支持) + * @details 该函数用于机械臂末端在当前位姿的基础上沿某坐标系(工具或工作)进行位移或旋转运动。 + * @param handle 机械臂控制句柄 + * @param offset 位置姿态偏移,位置单位:米,姿态单位:弧度 + * @param v 速度百分比系数,1~100 + * @param r 交融半径百分比系数,0~100。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param frame_type 参考坐标系类型:0-工作,1-工具 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后才返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movel_offset(rm_robot_handle *handle,rm_pose_t offset, int v, int r, int trajectory_connect, int frame_type, int block); +/** + * @brief 样条曲线运动 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @note 样条曲线运动需至少连续下发三个点位(trajectory_connect设置为1),否则运动轨迹为直线 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_moves(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 笛卡尔空间圆弧运动 + * + * @param handle 机械臂控制句柄 + * @param pose_via 中间点位姿,位置单位:米,姿态单位:弧度 + * @param pose_to 终点位姿 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param loop 规划圈数,目前默认0. + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movec(rm_robot_handle *handle,rm_pose_t pose_via, rm_pose_t pose_to, int v, int r, int loop, int trajectory_connect, int block); +/** + * @brief 该函数用于关节空间运动到目标位姿 + * + * @param handle 机械臂控制句柄 + * @param pose 目标位姿,位置单位:米,姿态单位:弧度。 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param r 轨迹交融半径,目前默认0。 + * @param trajectory_connect 轨迹连接标志 + * - 0:立即规划并执行轨迹,不与后续轨迹连接。 + * - 1:将当前轨迹与下一条轨迹一起规划,但不立即执行。阻塞模式下,即使发送成功也会立即返回。 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + - -6: 机械臂停止运动规划,外部发送了停止运动指令。 + */ +RM_INTERFACE_EXPORT int rm_movej_p(rm_robot_handle *handle,rm_pose_t pose, int v, int r, int trajectory_connect, int block); +/** + * @brief 角度不经规划,直接通过CANFD透传给机械臂 + * @details 角度透传到 CANFD,若指令正确,机械臂立即执行 + * 备注: + * 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + * 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + * I系列有线网口周期最快可达2ms,提供了更高的实时性。 + * @param handle 机械臂控制句柄 + * @param joint 关节1~7目标角度数组,单位:° + * @param follow true-高跟随,false-低跟随。若使用高跟随,透传周期要求不超过 10ms。 + * @param expand 如果存在通用扩展轴,并需要进行透传,可使用该参数进行透传发送。 + * @param trajectory_mode 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + * @param radio 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~100,曲线拟合模式下取值范围0~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movej_canfd(rm_robot_handle *handle, float *joint, bool follow, int expand, int trajectory_mode=0, int radio=0); +/** + * @brief 位姿不经规划,直接通过CANFD透传给机械臂 + * @details 当目标位姿被透传到机械臂控制器时,控制器首先尝试进行逆解计算。 + * 若逆解成功且计算出的各关节角度与当前角度差异不大,则直接下发至关节执行,跳过额外的轨迹规划步骤。 + * 这一特性适用于需要周期性调整位姿的场景,如视觉伺服等应用。 + * 备注: + * 透传效果受通信周期和轨迹平滑度影响,因此要求通信周期稳定,避免大幅波动。 + * 用户在使用此功能时,建议进行良好的轨迹规划,以确保机械臂的稳定运行。 + * I系列有线网口周期最快可达2ms,提供了更高的实时性。 + * @param handle 机械臂控制句柄 + * @param pose 位姿 (优先采用四元数表达) + * @param follow true-高跟随,false-低跟随。若使用高跟随,透传周期要求不超过 10ms。 + * @param trajectory_mode 高跟随模式下,0-完全透传模式、1-曲线拟合模式、2-滤波模式 + * @param radio 曲线拟合模式和滤波模式下的平滑系数(数值越大效果越好),滤波模式下取值范围0~100,曲线拟合模式下取值范围0~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movep_canfd(rm_robot_handle *handle, rm_pose_t pose, bool follow, int trajectory_mode=0, int radio=0); +/** + * @brief 关节空间跟随运动 + * @param handle 机械臂控制句柄 + * @param joint 关节1~7目标角度数组,单位:° + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movej_follow(rm_robot_handle *handle,float *joint); +/** + * @brief 笛卡尔空间跟随运动 + * @param handle 机械臂控制句柄 + * @param pose 位姿 (优先采用四元数表达) + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + */ +RM_INTERFACE_EXPORT int rm_movep_follow(rm_robot_handle *handle, rm_pose_t pose); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmMotionControl 机械臂运动控制指令类 + * + * 控制运动的急停、缓停、暂停、继续、清除轨迹以及查询当前规划类型 + * @{ + */ +/** + * @brief 轨迹缓停,在当前正在运行的轨迹上停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_slow_stop(rm_robot_handle *handle); +/** + * @brief 轨迹急停,关节最快速度停止,轨迹不可恢复 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_stop(rm_robot_handle *handle); +/** + * @brief 轨迹暂停,暂停在规划轨迹上,轨迹可恢复 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_pause(rm_robot_handle *handle); +/** + * @brief 轨迹暂停后,继续当前轨迹运动 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_continue(rm_robot_handle *handle); +/** + * @brief 清除当前轨迹 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 必须在暂停后使用,否则机械臂会发生意外!!!! + */ +RM_INTERFACE_EXPORT int rm_set_delete_current_trajectory(rm_robot_handle *handle); +/** + * @brief 清除所有轨迹 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 必须在暂停后使用,否则机械臂会发生意外!!!! + */ +RM_INTERFACE_EXPORT int rm_set_arm_delete_trajectory(rm_robot_handle *handle); +/** + * @brief 获取当前正在规划的轨迹信息 + * + * @param handle 机械臂控制句柄 + * @param type 返回的规划类型 + * @param data 无规划和关节空间规划为当前关节1~7角度数组;笛卡尔空间规划则为当前末端位姿 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_current_trajectory(rm_robot_handle *handle,rm_arm_current_trajectory_e *type,float *data); +/** @} */ // 结束组的定义 + +/** + * @defgroup ArmTeachMove 机械臂示教指令类 + * + * 关节、位置、姿态的示教及步进控制 + * @{ + */ +/** + * @brief 关节步进 + * + * @param handle 机械臂控制句柄 + * @param joint_num 关节序号,1~7 + * @param step 步进的角度, + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_step(rm_robot_handle *handle,int joint_num, float step, int v, int block); +/** + * @brief 当前工作坐标系下,位置步进 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param step 步进的距离,单位m,精确到0.001mm + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_pos_step(rm_robot_handle *handle, rm_pos_teach_type_e type, float step, int v, int block); +/** + * @brief 当前工作坐标系下,姿态步进 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param step 步进的弧度,单位rad,精确到0.001rad + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_ort_step(rm_robot_handle *handle, rm_ort_teach_type_e type, float step, int v, int block); +/** + * @brief 切换示教运动坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame_type 0: 工作坐标系运动, 1: 工具坐标系运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_teach_frame(rm_robot_handle *handle, int frame_type); +/** + * @brief 获取示教参考坐标系 + * + * @param handle 机械臂控制句柄 + * @param frame_type 0: 工作坐标系运动, 1: 工具坐标系运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_teach_frame(rm_robot_handle *handle,int *frame_type); +/** + * @brief 关节示教 + * + * @param handle 机械臂控制句柄 + * @param joint_num 示教关节的序号,1~7 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 速度比例1~100,即规划速度和加速度占关节最大线转速和加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_joint_teach(rm_robot_handle *handle,int joint_num, int direction, int v); +/** + * @brief 当前工作坐标系下,笛卡尔空间位置示教 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 即规划速度和加速度占机械臂末端最大线速度和线加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_pos_teach(rm_robot_handle *handle,rm_pos_teach_type_e type, int direction, int v); +/** + * @brief 当前工作坐标系下,笛卡尔空间姿态示教 + * + * @param handle 机械臂控制句柄 + * @param type 示教类型 + * @param direction 示教方向,0-负方向,1-正方向 + * @param v 速度比例1~100,即规划速度和加速度占机械臂末端最大角速度和角加速度的百分比 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 参考坐标系默认为当前工作坐标系,可调用rm_set_teach_frame修改为工具坐标系, + */ +RM_INTERFACE_EXPORT int rm_set_ort_teach(rm_robot_handle *handle,rm_ort_teach_type_e type, int direction, int v); +/** + * @brief 示教停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_stop_teach(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ControllerConfig 系统配置 + * + * 控制器状态获取、电源控制、错误清除、有线网口IP地址配置、软件信息获取 + * @{ + */ +/** + * @brief 获取控制器状态 + * + * @param handle 机械臂控制句柄 + * @param voltage 返回的电压 + * @param current 返回的电流 + * @param temperature 返回的温度 + * @param err_flag 控制器运行错误代码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_controller_state(rm_robot_handle *handle, float *voltage, float *current, float *temperature, int *err_flag); +/** + * @brief 设置机械臂电源 + * + * @param handle 机械臂控制句柄 + * @param arm_power 1-上电状态,0 断电状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_arm_power(rm_robot_handle *handle, int arm_power); +/** + * @brief 读取机械臂电源状态 + * + * @param handle 机械臂控制句柄 + * @param power_state 获取到的机械臂电源状态,1-上电状态,0 断电状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_power_state(rm_robot_handle *handle, int *power_state); +/** + * @brief 读取控制器的累计运行时间 + * + * @param handle 机械臂控制句柄 + * @param day 读取到的时间 + * @param hour 读取到的时间 + * @param min 读取到的时间 + * @param sec 读取到的时间 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_system_runtime(rm_robot_handle *handle, int *day, int *hour, int *min, int *sec); +/** + * @brief 清零控制器的累计运行时间 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_system_runtime(rm_robot_handle *handle); +/** + * @brief 读取关节的累计转动角度 + * + * @param handle 机械臂控制句柄 + * @param joint_odom 各关节累计的转动角度,单位° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_odom(rm_robot_handle *handle, float *joint_odom); +/** + * @brief 清零关节累计转动的角度 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_joint_odom(rm_robot_handle *handle); +/** + * @brief 配置有线网口 IP 地址 + * + * @param handle 机械臂控制句柄 + * @param ip 有线网口 IP 地址 + * @param netmask 有线网口子网掩码 + * @param gw 有线网口网关地址 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_NetIP(rm_robot_handle *handle, const char* ip, const char* netmask, const char* gw); +/** + * @brief 清除系统错误 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_system_err(rm_robot_handle *handle); +/** + * @brief 读取机械臂软件信息 + * + * @param handle 机械臂控制句柄 + * @param software_info 机械臂软件信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_arm_software_info(rm_robot_handle *handle,rm_arm_software_version_t *software_info); +/** + * @brief 查询控制器RS485模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0-代表默认 RS485 串行通讯,1-代表 modbus-RTU 主站模式,2-代表 modbus-RTU 从站模式; + * @param baudrate 波特率 + * @param timeout modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持此接口 + */ +RM_INTERFACE_EXPORT int rm_get_controller_RS485_mode(rm_robot_handle *handle, int* mode, int* baudrate, int* timeout); +/** + * @brief 查询工具端 RS485 模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0-代表默认 RS485 串行通讯 1-代表 modbus-RTU 主站模式 + * @param baudrate 波特率 + * @param timeout modbus 协议超时时间,单位 100ms,仅在 modbus-RTU 模式下提供此字段 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持此接口 + */ +RM_INTERFACE_EXPORT int rm_get_tool_RS485_mode(rm_robot_handle *handle, int* mode, int* baudrate, int* timeout); +/** + * @brief 查询关节软件版本号 + * + * @param handle 机械臂控制句柄 + * @param version 获取到的各关节软件版本号数组,需转换为十六进制,例如获取某关节版本为54536,转换为十六进制为D508,则当前关节的版本号为 Vd5.0.8(三代控制器) + * @param joint_v 获取到的各关节软件版本号字符串数组(四代控制器) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_joint_software_version(rm_robot_handle *handle,int *version, rm_version_t *joint_v); +RM_INTERFACE_EXPORT int rm_get_joint_software_version(rm_robot_handle *handle,int *version); +/** + * @brief 查询末端接口板软件版本号 + * + * @param handle 机械臂控制句柄 + * @param version (三代控制器)获取到的末端接口板软件版本号,需转换为十六进制,例如获取到版本号393,转换为十六进制为189,则当前关节的版本号为 V1.8.9 + * @param end_v (四代控制器)获取到的末端接口板软件版本号字符串 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_software_version(rm_robot_handle *handle, int *version, rm_version_t *end_v); +RM_INTERFACE_EXPORT int rm_get_tool_software_version(rm_robot_handle *handle, int *version); +/** @} */ // 结束组的定义 + +/** + * @defgroup CommunicationConfig 配置通讯内容 + * + * 机械臂控制器可通过网口、WIFI、RS232-USB 接口和 RS485 接口与用户通信,用户使用时无需切换,可使用上述任一接口, + * 控制器收到指令后,若指令格式正确,则会通过相同的接口反馈数据。 + * @{ + */ +/** + * @brief 配置 wifiAP 模式 + * + * @param handle 机械臂控制句柄 + * @param wifi_name wifi名称 + * @param password wifi密码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + * @attention 设置成功后蜂鸣器响,手动重启控制器进入 WIFIAP 模式。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_ap(rm_robot_handle *handle, const char* wifi_name, const char* password); +/** + * @brief 配置WiFi STA模式 + * + * @param handle 机械臂控制句柄 + * @param router_name 路由器名称 + * @param password 路由器Wifi密码 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + * @attention 设置成功后蜂鸣器响,手动重启控制器进入 WIFISTA 模式。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_sta(rm_robot_handle *handle, const char* router_name, const char* password); + +/** + * @brief 控制器RS485接口波特率设置,设置成功后蜂鸣器响 + * + * @param handle 机械臂控制句柄 + * @param baudrate 波特率:9600,19200,38400,115200和460800,若用户设置其他数据,控制器会默认按照460800处理。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 四代控制器不支持该接口 + * @attention 该指令下发后控制器会记录当前波特率,断电重启后仍会使用该波特率对外通信。 + */ +RM_INTERFACE_EXPORT int rm_set_RS485(rm_robot_handle *handle, int baudrate); +/** + * @brief 获取有线网卡信息,未连接有线网卡则会返回无效数据 + * + * @param handle 机械臂控制句柄 + * @param ip 网络地址 + * @param mask 子网掩码 + * @param mac MAC地址 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_wired_net(rm_robot_handle *handle, char * ip, char * mask, char * mac); +/** + * @brief 查询无线网卡网络信息 + * + * @param handle 机械臂控制句柄 + * @param wifi_net 无线网卡网络信息结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 结构体中的channel值只有在AP模式时才可获取到,标识 wifi 热点的物理信道号 + */ +RM_INTERFACE_EXPORT int rm_get_wifi_net(rm_robot_handle *handle, rm_wifi_net_t *wifi_net); +/** + * @brief 恢复网络出厂设置 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_net_default(rm_robot_handle *handle); +/** + * @brief 配置关闭 wifi 功能,需要重启后生效 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_wifi_close(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ControllerIOConfig 控制器IO配置及获取 + * + * 机械臂控制器提供IO端口,用于与外部设备交互。以下是具体的IO端口配置和特性: + * + * - 数字IO: + * - 数量: 4路 + * - 功能: DO/DI复用(数字输出/数字输入) + * - 电压范围: 可配置为0~24V + * @{ + */ +/** + * @brief 设置数字IO模式 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~4 + * @param io_mode 模式: + * 0-通用输入模式,1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、 + * 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式、7-输入进入力只动位置拖动模式(六维力版本可配置)、 + * 8-输入进入力只动姿态拖动模式(六维力版本可配置)、9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、 + * 10-输入外部轴最大软限位复用模式(外部轴模式可配置)、11-输入外部轴最小软限位复用模式(外部轴模式可配置)、 + * 12-输入初始位姿功能复用模式、13-输出碰撞功能复用模式、14-实时调速功能复用模式 + * @param io_speed_mode 模式取值1或2(只有io_mode为14时生效): + * 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值。 + * 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + * @param io_speed 速度取值范围0-100(只有io_mode为14时生效) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_IO_mode(rm_robot_handle *handle, int io_num, int io_mode, int io_speed_mode=0, int io_speed=0); +/** + * @brief 设置数字IO输出 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~4 + * @param state IO 状态,1-输出高,0-输出低 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_DO_state(rm_robot_handle *handle, int io_num, int state); +/** + * @brief + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~4 + * @param state IO 状态 + * @param io_mode 模式: + * 0-通用输入模式,1-通用输出模式、2-输入开始功能复用模式、3-输入暂停功能复用模式、 + * 4-输入继续功能复用模式、5-输入急停功能复用模式、6-输入进入电流环拖动复用模式、7-输入进入力只动位置拖动模式(六维力版本可配置)、 + * 8-输入进入力只动姿态拖动模式(六维力版本可配置)、9-输入进入力位姿结合拖动复用模式(六维力版本可配置)、 + * 10-输入外部轴最大软限位复用模式(外部轴模式可配置)、11-输入外部轴最小软限位复用模式(外部轴模式可配置)、 + * 12-输入初始位姿功能复用模式13-输出碰撞功能复用模式、14-实时调速功能复用模式 + * @param io_speed_mode 模式取值1或2(只有io_mode为14时生效): + * 1表示单次触发模式,单次触发模式下当IO拉低速度设置为speed参数值,IO恢复高电平速度设置为初始值。 + * 2表示连续触发模式,连续触发模式下IO拉低速度设置为speed参数值,IO恢复高电平速度维持当前值 + * @param io_speed 速度取值范围0-100(只有io_mode为14时生效) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_state(rm_robot_handle *handle, int io_num, int* state, int* mode, int* io_speed_mode=nullptr, int* io_speed=nullptr); +/** + * @brief 获取所有 IO 输入状态 + * + * @param handle 机械臂控制句柄 + * @param DI_state 数字输入状态,1:高,0:低,-1:该端口不是输入模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_input(rm_robot_handle *handle, int *DI_state); +/** + * @brief 获取所有 IO 输出状态 + * + * @param handle 机械臂控制句柄 + * @param DO_state 数字输出状态,1:高,0:低,-1:该端口不是输出模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_IO_output(rm_robot_handle *handle, int *DO_state); +/** + * @brief 设置控制器电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,2:12V,3:24V + * @param start_enable true:开机启动时输出此配置电压,false:取消开机启动即配置电压 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_voltage(rm_robot_handle *handle, int voltage_type, bool start_enable); +/** + * @brief 获取控制器电源输出类 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,2:12V,3:24V + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_voltage(rm_robot_handle *handle, int *voltage_type); +/** @} */ // 结束组的定义 + +/** + * @defgroup ToolIOConfig 末端工具 IO 控制 + * + * 机械臂末端工具端提供多种IO端口,用于与外部设备交互。以下是端口的具体配置和特性: + * - 电源输出: + * - 数量: 1路 + * - 可配置电压: 0V, 5V, 12V, 24V + * + * - 数字IO: + * - 数量: 2路 + * - 可配置性: 输入/输出均可配置 + * - 输入特性: + * - 参考电平: 12V~24V + * - 输出特性: + * - 电压范围: 5~24V(与输出电压一致) + * + * - 通讯接口: + * - 数量: 1路 + * - 可配置协议: RS485 + * @{ + */ +/** + * @brief 设置工具端数字 IO 输出 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~2 + * @param state IO 状态,1-输出高,0-输出低 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_DO_state(rm_robot_handle *handle, int io_num, int state); +/** + * @brief 设置工具端数字 IO 模式 + * + * @param handle 机械臂控制句柄 + * @param io_num IO 端口号,范围:1~2 + * @param io_mode 模式,0-输入状态,1-输出状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_tool_IO_mode(rm_robot_handle *handle, int io_num, int io_mode); +/** + * @brief 获取数字 IO 状态 + * + * @param handle 机械臂控制句柄 + * @param state 0-输入模式,1-输出模式 + * @param mode 0-低,1-高 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_IO_state(rm_robot_handle *handle, int* state, int* mode); +/** + * @brief 设置工具端电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,1:5V,2:12V,3:24V, + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 电源输出设置为 5V 时,工具端的IO 暂不支持输入输出功能 + */ +RM_INTERFACE_EXPORT int rm_set_tool_voltage(rm_robot_handle *handle, int voltage_type); +/** + * @brief 获取工具端电源输出 + * + * @param handle 机械臂控制句柄 + * @param voltage_type 电源输出类型,0:0V,1:5V,2:12V,3:24V, + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_tool_voltage(rm_robot_handle *handle, int *voltage_type); +/** @} */ // 结束组的定义 + +/** + * @defgroup GripperControl 末端工具—手爪控制 + * + * 睿尔曼机械臂末端配备了因时机器人公司的 EG2-4C2 手爪,为了便于用户操作手爪,机械臂控制器 + * 对用户开放了手爪的控制协议(手爪控制协议与末端modbus 功能互斥) + * @{ + */ +/** + * @brief 设置手爪行程,即手爪开口的最大值和最小值,设置成功后会自动保存,手爪断电不丢失 + * + * @param handle 机械臂控制句柄 + * @param min_limit 手爪开口最小值,范围:0~1000,无单位量纲 + * @param max_limit 手爪开口最大值,范围:0~1000,无单位量纲 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_route(rm_robot_handle *handle, int min_limit, int max_limit); +/** + * @brief 松开手爪,即手爪以指定的速度运动到开口最大处 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪松开速度,范围 1~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_release(rm_robot_handle *handle, int speed, bool block, int timeout); +/** + * @brief 手爪力控夹取,手爪以设定的速度和力夹取,当夹持力超过设定的力阈值后,停止夹取 + * + * @param handle 机械臂控制句柄 + * @param speed 手爪夹取速度,范围 1~1000,无单位量纲 + * @param force 力控阈值,范围:50~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_pick(rm_robot_handle *handle, int speed, int force, bool block, int timeout); +/** + * @brief + * + * @param handle 机械臂控制句柄 + * @param speed 手爪夹取速度,范围 1~1000,无单位量纲 + * @param force 力控阈值,范围:50~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_pick_on(rm_robot_handle *handle, int speed, int force, bool block, int timeout); +/** + * @brief 设置手爪达到指定位置 + * @details 手爪到达指定位置,当当前开口小于指定开口时,手爪以指定速度松开到指定开口位置;当当前开口大于指定开口时, + * 手爪以指定速度和力矩闭合往指定开口处闭合,当夹持力超过力矩阈值或者达到指定位置后,手爪停止。 + * @param handle 机械臂控制句柄 + * @param position 手爪开口位置,范围:1~1000,无单位量纲 + * @param block true 表示阻塞模式,等待控制器返回夹爪到位指令;false 表示非阻塞模式,不接收夹爪到位指令; + * @param timeout 阻塞模式:设置等待夹爪到位超时时间,单位:秒 + * 非阻塞模式:0-发送后立即返回;其他值-接收设置成功指令后返回; + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4:超时 + */ +RM_INTERFACE_EXPORT int rm_set_gripper_position(rm_robot_handle *handle, int position, bool block, int timeout); +/** + * @brief 查询夹爪状态 + * + * @param handle 机械臂控制句柄 + * @param state 夹爪状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @attention 此接口默认不更新数据,从首次控制夹爪开始后,使能更新状态,如果此时控制灵巧手或打开末端modbus功能,将不再更新数据。另外夹爪需要支持最新的固件,方可支持此功能 + */ +RM_INTERFACE_EXPORT int rm_get_gripper_state(rm_robot_handle *handle, rm_gripper_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForceSensor 末端传感器六维力 + * + * 睿尔曼机械臂六维力版末端配备集成式六维力传感器,无需外部走线,用户可直接通过协议对六维力进行操作, + * 获取六维力数据。如下图所示,正上方为六维力的 Z 轴,航插反方向为六维力的 Y 轴,坐标系符合右手定则。 + * 机械臂位于零位姿态时,工具坐标系与六维力的坐标系方向一致。 + * 另外,六维力额定力 200N,额定力矩 8Nm,过载水平 300%FS,工作温度 5~80℃,准度 0.5%FS。使用过程中 + * 注意使用要求,防止损坏六维力传感器。 + * @{ + */ +/** + * @brief 查询当前六维力传感器得到的力和力矩信息:Fx,Fy,Fz,Mx,My,Mz + * + * @param handle 机械臂控制句柄 + * @param data 力传感器数据结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_force_data(rm_robot_handle *handle, rm_force_data_t *data); +/** + * @brief 将六维力数据清零,标定当前状态下的零位 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_force_data(rm_robot_handle *handle); +/** + * @brief 自动设置六维力重心参数 + * @details 设置六维力重心参数,六维力重新安装后,必须重新计算六维力所受到的初始力和重心。分别在不同姿态下,获取六维力的数据, + * 用于计算重心位置。该指令下发后,机械臂以固定的速度运动到各标定点。 + * 以RM65机械臂为例,四个标定点的关节角度分别为: + * 位置1关节角度:{0,0,-60,0,60,0} + * 位置2关节角度:{0,0,-60,0,-30,0} + * 位置3关节角度:{0,0,-60,0,-30,180} + * 位置4关节角度:{0,0,-60,0,-120,0} + * @attention 必须保证在机械臂静止状态下标定; + * 该过程不可中断,中断后必须重新标定。 + * @param handle 机械臂控制句柄 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_sensor(rm_robot_handle *handle, bool block); +/** + * @brief 手动标定六维力数据 + * @details 六维力重新安装后,必须重新计算六维力所受到的初始力和重心。该手动标定流程,适用于空间狭窄工作区域,以防自动标定过程中 + * 机械臂发生碰撞,用户可以手动选取四个位置下发,当下发完四个点后,机械臂开始自动沿用户设置的目标运动,并在此过程中计算六维力重心。 + * @attention 上述4个位置必须按照顺序依次下发,当下发完位置4后,机械臂开始自动运行计算重心。 + * @param handle 机械臂控制句柄 + * @param count 点位;1~4 + * @param joint 关节角度,单位:° + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 计算成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_manual_set_force(rm_robot_handle *handle, int count, float *joint, bool block); +/** + * @brief 停止标定力传感器重心 + * @details 在标定力传感器过程中,如果发生意外,发送该指令,停止机械臂运动,退出标定流程 + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_set_force_sensor(rm_robot_handle *handle); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForceSensor 末端传感器一维力 + * + * 睿尔曼机械臂末端接口板集成了一维力传感器,可获取 Z 方向的力,量程200N,准度 0.5%FS。 + * @{ + */ +/** + * @brief 查询末端一维力数据 + * + * @param handle 机械臂控制句柄 + * @param data 一维力数据结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非力控版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_get_Fz(rm_robot_handle *handle, rm_fz_data_t *data); +/** + * @brief 清零末端一维力数据,清空一维力数据后,后续所有获取到的数据都是基于当前的偏置。 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_clear_Fz(rm_robot_handle *handle); +/** + * @brief 自动标定一维力数据 + * @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。 + * 分别在不同姿态下,获取一维力的数据,用于计算重心位置,该步骤对于基于一维力的力位混合控制操作具有重要意义。 + * @param handle 机械臂控制句柄 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_auto_set_Fz(rm_robot_handle *handle, bool block); +/** + * @brief 手动标定一维力数据 + * @details 设置一维力重心参数,一维力重新安装后,必须重新计算一维力所受到的初始力和重心。该手动标定流程, + * 适用于空间狭窄工作区域,以防自动标定过程中机械臂发生碰撞,用户可以手动选取2个位置下发,当下发完后, + * 机械臂开始自动沿用户设置的目标运动,并在此过程中计算一维力重心。 + * @param handle 机械臂控制句柄 + * @param joint1 位置1关节角度数组,单位:度 + * @param joint2 位置2关节角度数组,单位:度 + * @param block true 表示阻塞模式,等待标定完成后返回;false 表示非阻塞模式,发送后立即返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_manual_set_Fz(rm_robot_handle *handle, float *joint1, float *joint2, bool block); +/** @} */ // 结束组的定义 + +/** + * @defgroup DragTeach 拖动示教 + * + * 睿尔曼机械臂在拖动示教过程中,可记录拖动的轨迹点,并根据用户的指令对轨迹进行复现。 + * @{ + */ +/** + * @brief 拖动示教开始 + * + * @param handle 机械臂控制句柄 + * @param trajectory_record 拖动示教时记录轨迹,0-不记录,1-记录轨迹 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_start_drag_teach(rm_robot_handle *handle, int trajectory_record); +/** + * @brief 拖动示教结束 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_drag_teach(rm_robot_handle *handle); +/** + * @brief 开始复合模式拖动示教 + * @attention 仅支持三代控制器,四代控制器使用rm_start_multi_drag_teach_new + * @param handle 机械臂控制句柄 + * @param mode 拖动示教模式 0-电流环模式,1-使用末端六维力,只动位置,2-使用末端六维力,只动姿态,3-使用末端六维力,位置和姿态同时动 + * @param singular_wall 仅在六维力模式拖动示教中生效,用于指定是否开启拖动奇异墙,0表示关闭拖动奇异墙,1表示开启拖动奇异墙 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口。 + * @note 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + */ +RM_INTERFACE_EXPORT int rm_start_multi_drag_teach(rm_robot_handle *handle, int mode, int singular_wall); +/** + * @brief 开始复合模式拖动示教-新参数 + * + * @param handle 机械臂控制句柄 + * @param teach_state 复合拖动示教参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @note 失败的可能原因: + - 当前机械臂非六维力版本(六维力拖动示教)。 + - 机械臂当前处于 IO 急停状态 + - 机械臂当前处于仿真模式 + - 输入参数有误 + - 使用六维力模式拖动示教时,当前已处于奇异区 + */ +RM_INTERFACE_EXPORT int rm_start_multi_drag_teach(rm_robot_handle *handle, rm_multi_drag_teach_t teach_state); +/** + * @brief 设置电流环拖动示教灵敏度 + * + * @param handle 机械臂控制句柄 + * @param grade 等级,0到100,表示0~100%,当设置为100时保持初始状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_drag_teach_sensitivity(rm_robot_handle *handle, int grade); +/** + * @brief 获取电流环拖动示教灵敏度 + * + * @param handle 机械臂控制句柄 + * @param grade 等级,0到100,表示0~100%,当设置为100时保持初始状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_drag_teach_sensitivity(rm_robot_handle *handle, int *grade); +/** + * @brief 运动到轨迹起点 + * @details 轨迹复现前,必须控制机械臂运动到轨迹起点,如果设置正确,机械臂将以20%的速度运动到轨迹起点 + * @param handle 机械臂控制句柄 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @see rm_run_drag_trajectory + */ +RM_INTERFACE_EXPORT int rm_drag_trajectory_origin(rm_robot_handle *handle, int block); +/** + * @brief 轨迹复现开始 + * + * @param handle 机械臂控制句柄 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,根据运动时间设置,单位为秒。 + * @attention 使用单线程阻塞模式时,请设置超时时间确保轨迹在超时时间内运行结束返回 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误,请确保机械臂当前位置为拖动示教起点。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + * @attention 必须在拖动示教结束后才能使用,同时保证机械臂位于拖动示教的起点位置,可调用rm_drag_trajectory_origin接口运动至起点位置 + * @see rm_drag_trajectory_origin + */ +RM_INTERFACE_EXPORT int rm_run_drag_trajectory(rm_robot_handle *handle, int block); +/** + * @brief 控制机械臂在轨迹复现过程中的暂停 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_pause_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 控制机械臂在轨迹复现过程中暂停之后的继续, + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_continue_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 控制机械臂在轨迹复现过程中的停止 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_drag_trajectory(rm_robot_handle *handle); +/** + * @brief 保存拖动示教轨迹 + * + * @param handle 机械臂控制句柄 + * @param name 轨迹要保存的文件路径及名称,长度不超过300个字符,例: c:/rm_test.txt + * @param num 轨迹点数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_save_trajectory(rm_robot_handle *handle, const char* name, int *num); +/** + * @brief 力位混合控制 + * @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + * 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + * @param handle 机械臂控制句柄 + * @param sensor 0-一维力;1-六维力 + * @param mode 0-基坐标系力控;1-工具坐标系力控; + * @param direction 力控方向;0-沿X轴;1-沿Y轴;2-沿Z轴;3-沿RX姿态方向;4-沿RY姿态方向;5-沿RZ姿态方向 + * @param N 力的大小,单位N + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_position(rm_robot_handle *handle, int sensor, int mode, int direction, float N); +/** + * @brief 力位混合控制-新参数 + * @details 在笛卡尔空间轨迹规划时,使用该功能可保证机械臂末端接触力恒定,使用时力的方向与机械臂运动方向不能在同一方向。 + * 开启力位混合控制,执行笛卡尔空间运动,接收到运动完成反馈后,需要等待2S后继续下发下一条运动指令。 + * @param handle 机械臂控制句柄 + * @param param 力位混合控制参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_force_position(rm_robot_handle *handle, rm_force_position_t param); +/** + * @brief 结束力位混合控制 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_force_position(rm_robot_handle *handle); +/** + * @brief 设置六维力拖动示教模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0表示快速拖动模式 1表示精准拖动模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_set_force_drag_mode(rm_robot_handle *handle, int mode); +/** + * @brief 获取六维力拖动示教模式 + * + * @param handle 机械臂控制句柄 + * @param mode 0表示快速拖动模式 1表示精准拖动模式 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。处理建议:1、联系睿尔曼公司技术支持确认控制器版本是否支持此功能; + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 非六维力版本机械臂,不支持此功能。 + */ +RM_INTERFACE_EXPORT int rm_get_force_drag_mode(rm_robot_handle *handle, int *mode); +/** @} */ // 结束组的定义 + +/** + * @defgroup HandControl 五指灵巧手 + * + * 睿尔曼机械臂末端配置因时的五指灵巧手,可通过协议对灵巧手进行设置。 + * @{ + */ +/** + * @brief 设置灵巧手目标手势序列号 + * + * @param handle 机械臂控制句柄 + * @param posture_num 预先保存在灵巧手内的手势序号,范围:1~40 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 超时未返回 + */ +RM_INTERFACE_EXPORT int rm_set_hand_posture(rm_robot_handle *handle, int posture_num, bool block, int timeout); +/** + * @brief 设置灵巧手目标手势序列号 + * + * @param handle 机械臂控制句柄 + * @param seq_num 预先保存在灵巧手内的手势序号,范围:1~40 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 超时未返回 + */ +RM_INTERFACE_EXPORT int rm_set_hand_seq(rm_robot_handle *handle, int seq_num, bool block, int timeout); +/** + * @brief 设置灵巧手各自由度角度 + * @details 设置灵巧手角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + * @param handle 机械臂控制句柄 + * @param hand_angle 手指角度数组,范围:0~1000. 另外,-1代表该自由度不执行任何操作,保持当前状态 + * @param block true 表示阻塞模式,等待灵巧手运动结束后返回;false 表示非阻塞模式,发送后立即返回 + * @param timeout 阻塞模式下超时时间设置,单位:秒 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为灵巧手 + - -5: 超时未返回。 */ +RM_INTERFACE_EXPORT int rm_set_hand_angle(rm_robot_handle *handle, const int *hand_angle, bool block, int timeout); +/** + * @brief 设置灵巧手各自由度跟随角度 + * @details 设置灵巧手跟随角度,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转 + * @param handle 机械臂控制句柄 + * @param hand_angle 手指角度数组,最大表示范围为-32768到+32767,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-2000 + * @param block 0:表示非阻塞模式,发送成功后返回,1:表示阻塞模式,接收设置成功指令后返回。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_follow_angle(rm_robot_handle *handle, const int *hand_angle, bool block); +/** + * @brief 灵巧手位置跟随控制 + * @details 设置灵巧手跟随位置,灵巧手有6个自由度,从1~6分别为小拇指,无名指,中指,食指,大拇指弯曲,大拇指旋转,最高50Hz的控制频率 + * @param handle 机械臂控制句柄 + * @param hand_pos 手指位置数组,最大范围为0-65535,按照灵巧手厂商定义的角度做控制,例如因时的范围为0-1000 + * @param block 0:表示非阻塞模式,发送成功后返回,1:表示阻塞模式,接收设置成功指令后返回。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_follow_pos(rm_robot_handle *handle, const int *hand_pos, bool block); +/** + * @brief 设置灵巧手速度 + * + * @param handle 机械臂控制句柄 + * @param speed 手指速度,范围:1~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_speed(rm_robot_handle *handle, int speed); +/** + * @brief 设置灵巧手力阈值 + * + * @param handle 机械臂控制句柄 + * @param hand_force 手指力,范围:1~1000 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_hand_force(rm_robot_handle *handle, int hand_force); +/** @} */ // 结束组的定义 + +/** + * @defgroup ModbusConfig Modbus 配置 + * + * 睿尔曼机械臂在控制器和末端接口板上各提供一个RS485通讯接口,这些接口可通过JSON协议配置为标准的Modbus RTU模式。 + * 在Modbus RTU模式下,用户可通过JSON协议对连接在端口上的外设进行读写操作。 + * + * @attention + * - 控制器的RS485接口在未配置为Modbus RTU模式时,可用于直接控制机械臂。 + * - Modbus RTU模式与机械臂控制模式不兼容。若需恢复机械臂控制模式,必须关闭该端口的Modbus RTU模式。 + * - 关闭Modbus RTU模式后,系统将自动切换回机械臂控制模式,使用波特率460800BPS,停止位1,数据位8,无校验。 + * + * 此外,I系列控制器还支持modbus-TCP主站配置,允许用户配置使用modbus-TCP主站,以连接外部设备的modbus-TCP从站。 + * + * @{ + */ +/** + * @brief 配置通讯端口ModbusRTU模式 + * @details 配置通讯端口ModbusRTU模式,机械臂启动后,要对通讯端口进行任何操作,必须先启动该指令,否则会返回报错信息。 + * 另外,机械臂会对用户的配置方式进行保存,机械臂重启后会自动恢复到用户断电之前配置的模式。 + * @param handle 机械臂控制句柄 + * @param port 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + * @param baudrate 波特率,支持 9600,115200,460800 三种常见波特率 + * @param timeout 超时时间,单位百毫秒。。对Modbus设备所有的读写指令,在规定的超时时间内未返回响应数据,则返回超时报错提醒。超时时间不能为0,若设置为0,则机械臂按1进行配置。 + * @note 其他配置默认为:数据位-8,停止位-1,奇偶校验-无 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_modbus_mode(rm_robot_handle *handle, int port, int baudrate, int timeout); +/** + * @brief 关闭通讯端口 Modbus RTU 模式 + * + * @param handle 机械臂控制句柄 + * @param port 通讯端口,0-控制器RS485端口为RTU主站,1-末端接口板RS485接口为RTU主站,2-控制器RS485端口为RTU从站 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_close_modbus_mode(rm_robot_handle *handle, int port); +/** + * @brief 配置连接 ModbusTCP 从站 + * + * @param handle 机械臂控制句柄 + * @param ip 从机IP地址 + * @param port 端口号 + * @param timeout 超时时间,单位毫秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_modbustcp_mode(rm_robot_handle *handle, const char *ip, int port, int timeout); +/** + * @brief 关闭通讯端口ModbusRTU模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_close_modbustcp_mode(rm_robot_handle *handle); +/** + * @brief 读线圈 + * + * @param handle 机械臂控制句柄 + * @param params 线圈读取参数结构体,该指令最多一次性支持读 8 个线圈数据,即返回的数据不会超过一个字节 + * @param data 返回线圈状态,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读离散量输入 + * + * @param handle 机械臂控制句柄 + * @param params 离散量输入读取参数结构体,该指令最多一次性支持读 8 个离散量数据,即返回的数据不会超过一个字节 + * @param data 返回离散量,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_input_status(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读保持寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 保持寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节 + * 的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + * @param data 返回寄存器数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_holding_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读输入寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 输入寄存器数据读取参数结构体,该指令每次只能读 1 个寄存器,即 2 个字节 + * 的数据,不可一次性读取多个寄存器数据,该结构体成员num无需设置 + * @param data 返回寄存器数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_input_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 写单圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 单圈数据写入参数结构体,该结构体成员num无需设置 + * @param data 要写入线圈的数据,数据类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_single_coil(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int data); +/** + * @brief 写单个寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 单个寄存器数据写入参数结构体,该结构体成员num无需设置 + * @param data 要写入寄存器的数据,类型:int16 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_single_register(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int data); +/** + * @brief 写多个寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个寄存器数据写入参数结构体。其中寄存器每次写的数量不超过10个,即该结构体成员num<=10。 + * @param data 要写入寄存器的数据数组,类型:byte。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 写多圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 多圈数据写入参数结构体。每次写的数量不超过 160 个,即该结构体成员num<=160。 + * @param data 要写入线圈的数据数组,类型:byte。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 写操作失败,超时时间内未获取到数据,或者指令内容错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多圈数据 + * + * @param handle 机械臂控制句柄 + * @param params 多圈数据读取参数结构体,要读的线圈的数量 8< num <= 120,该指令最多一次性支持读 120 个线圈数据, 即 15 个 byte + * @param data 返回线圈状态,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_coils(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多个保存寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个保存寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + * @param data 返回寄存器数据,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_holding_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** + * @brief 读多个输入寄存器 + * + * @param handle 机械臂控制句柄 + * @param params 多个输入寄存器读取参数结构体,要读的寄存器的数量 2 < num < 13,该指令最多一次性支持读 12 个寄存器数据, 即 24 个 byte + * @param data 返回寄存器数据,数据类型:int8 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 读取失败,超时时间内未获取到数据。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_multiple_input_registers(rm_robot_handle *handle, rm_peripheral_read_write_params_t params, int *data); +/** @} */ // 结束组的定义 + +/** + * @defgroup InstallPos 系统安装方式 + * + * 睿尔曼机械臂可支持不同形式的安装方式,但是安装方式不同,机器人的动力学模型参数和坐标系的方向也有所差别。 + * @{ + */ +/** + * @brief 设置安装方式参数 + * + * @param handle 机械臂控制句柄 + * @param x 旋转角,单位 ° + * @param y 俯仰角,单位 ° + * @param z 方位角,单位 ° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_install_pose(rm_robot_handle *handle, float x, float y, float z); +/** + * @brief 获取安装方式参数 + * + * @param handle 机械臂控制句柄 + * @param x 旋转角(out),单位 ° + * @param y 俯仰角(out),单位 ° + * @param z 方位角(out),单位 ° + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_install_pose(rm_robot_handle *handle, float *x, float *y, float *z); +/** @} */ // 结束组的定义 + +/** + * @defgroup ForcePositionControl 透传力位混合控制补偿 + * + * 针对睿尔曼带一维力和六维力版本的机械臂,用户除了可直接使用示教器调用底层的力位混合控制模块外,还可以将 + * 自定义的轨迹以周期性透传的形式结合底层的力位混合控制算法进行补偿。 + * + * @attention 该功能只适用于一维力传感器和六维力传感器机械臂版本 + * + * 透传效果和周期、轨迹是否平滑有关,周期要求稳定,防止出现较大波动,用户使用该指令时请做好轨迹规划,轨迹规划的 + * 平滑程度决定了机械臂的运行状态。基础系列 WIFI 和网口模式透传周期最快 20ms,USB 和 RS485 模式透传周期最快 10ms。 + * 高速网口的透传周期最快也可到 10ms,不过在使用该高速网口前,需要使用指令打开配置。另外 I 系列有线网口周期最快可达 2ms。 + * @{ + */ +/** + * @brief 开启透传力位混合控制补偿模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_start_force_position_move(rm_robot_handle *handle); +/** + * @brief 停止透传力位混合控制补偿模式 + * + * @param handle 机械臂控制句柄 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_stop_force_position_move(rm_robot_handle *handle); +/** + * @brief 透传力位混合补偿-角度方式 + * + * @param handle 机械臂控制句柄 + * @param joint 目标关节角度 + * @param sensor 所使用传感器类型,0-一维力,1-六维力 + * @param mode 模式,0-沿基坐标系,1-沿工具端坐标系 + * @param dir 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + * @param force 力的大小 单位N + * @param follow 是否高跟随 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move_joint(rm_robot_handle *handle,const float *joint,int sensor,int mode,int dir,float force, bool follow); +/** + * @brief 透传力位混合补偿-位姿方式 + * + * @param handle 机械臂控制句柄 + * @param pose 当前坐标系下目标位姿 + * @param sensor 所使用传感器类型,0-一维力,1-六维力 + * @param mode 模式,0-沿基坐标系,1-沿工具端坐标系 + * @param dir 力控方向,0~5分别代表X/Y/Z/Rx/Ry/Rz,其中一维力类型时默认方向为Z方向 + * @param force 力的大小 单位N + * @param follow 是否高跟随 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move_pose(rm_robot_handle *handle, rm_pose_t pose,int sensor,int mode,int dir,float force, bool follow); +/** + * @brief 透传力位混合补偿-新参数 + * + * @param handle 机械臂控制句柄 + * @param param 透传力位混合补偿参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_force_position_move(rm_robot_handle *handle, rm_force_position_move_t param); +/** @} */ // 结束组的定义 + +/** + * @defgroup LiftControl 升降机构 + * + * 升降机构速度开环控制、位置闭环控制及状态获取 + * @{ + */ +/** + * @brief 升降机构速度开环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,-100~100。 + - speed<0:升降机构向下运动 + - speed>0:升降机构向上运动 + - speed=0:升降机构停止运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_lift_speed(rm_robot_handle *handle, int speed); +/** + * @brief 升降机构位置闭环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,1~100 + * @param height 目标高度,单位 mm,范围:0~2600 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待升降机到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为升降机构。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_lift_height(rm_robot_handle *handle, int speed, int height, int block); +/** + * @brief 获取升降机构状态 + * + * @param handle 机械臂控制句柄 + * @param state 当前升降机构状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_lift_state(rm_robot_handle *handle, rm_expand_state_t *state); +/** @} */ // 结束组的定义 + +/** + * @defgroup ExpandControl 通用扩展关节 + * + * 扩展关节速度环控制、位置环控制及状态获取 + * @{ + */ +/** + * @brief 扩展关节状态获取 + * + * @param handle 机械臂控制句柄 + * @param state 扩展关节状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_expand_state(rm_robot_handle *handle, rm_expand_state_t *state); +/** + * @brief 扩展关节速度环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,-100~100。 + - speed<0:扩展关节反方向运动 + - speed>0:扩展关节正方向运动 + - speed=0:扩展关节停止运动 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_expand_speed(rm_robot_handle *handle, int speed); +/** + * @brief 扩展关节位置环控制 + * + * @param handle 机械臂控制句柄 + * @param speed 速度百分比,1~100 + * @param pos 扩展关节角度,单位度 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待升降机到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 当前到位设备校验失败,即当前到位设备不为扩展关节。 + - -5: 单线程模式超时未接收到返回,请确保超时时间设置合理。 + */ +RM_INTERFACE_EXPORT int rm_set_expand_pos(rm_robot_handle *handle, int speed, int pos, int block); +/** @} */ // 结束组的定义 + +/** + * @defgroup OnlineProgramming 在线编程 + * + * 包含在线编程文件下发、在线编程文件管理、全局路点管理等相关功能接口。 + * @{ + */ +/** + * @brief 文件下发 + * + * @param handle 机械臂控制句柄 + * @param project 文件下发参数配置结构体 + * @param errline 若运行失败,该参数返回有问题的工程行数,err_line 为 0,则代表校验数据长度不对 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 文件名称校验失败 + - -5: 文件读取失败 + - -6: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_send_project(rm_robot_handle *handle, rm_send_project_t project, int *errline); +/** + * @brief 规划过程中改变速度系数 + * + * @param handle 机械臂控制句柄 + * @param speed 速度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_plan_speed(rm_robot_handle *handle, int speed); + +/** + * @brief 获取在线编程列表 + * + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param trajectorys 在线编程程序列表 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_program_trajectory_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_program_trajectorys_t *trajectorys); + +/** + * @brief 开始运行指定编号轨迹 + * + * @param handle 机械臂控制句柄 + * @param id 运行指定的ID,1-100,存在轨迹可运行 + * @param speed 1-100,需要运行轨迹的速度,若设置为0,则按照存储的速度运行 + * @param block 阻塞设置 + * - 多线程模式: + * - 0:非阻塞模式,发送指令后立即返回。 + * - 1:阻塞模式,等待机械臂到达目标位置或规划失败后返回。 + * - 单线程模式: + * - 0:非阻塞模式。 + * - 其他值:阻塞模式并设置超时时间,单位为秒。 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 运行状态已停止但未接收到运行成功,是否在外部停止了轨迹。 + */ +RM_INTERFACE_EXPORT int rm_set_program_id_run(rm_robot_handle *handle, int id, int speed, int block); +/** + * @brief 查询在线编程运行状态 + * + * @param handle 机械臂控制句柄 + * @param run_state 在线编程运行状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 四代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_program_run_state(rm_robot_handle *handle, rm_program_run_state_t *run_state); +/** + * @brief 查询流程图运行状态 + * + * @param handle 机械臂控制句柄 + * @param run_state 流程图运行状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_flowchart_program_run_state(rm_robot_handle *handle, rm_flowchart_run_state_t *run_state); +/** + * @brief 删除指定编号编程文件 + * + * @param handle 机械臂控制句柄 + * @param id 指定编程轨迹的编号 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_program_trajectory(rm_robot_handle *handle, int id); +/** + * @brief 修改指定编号的编程文件 + * + * @param handle 机械臂控制句柄 + * @param id 指定在线编程轨迹编号 + * @param speed 更新后的规划速度比例 1-100 + * @param name 更新后的文件名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_program_trajectory(rm_robot_handle *handle, int id, int speed, const char* name); +/** + * @brief 设置 IO 默认运行编号 + * + * @param handle 机械臂控制句柄 + * @param id 设置 IO 默认运行的在线编程文件编号,支持 0-100,0 代表取消设置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_default_run_program(rm_robot_handle *handle, int id); +/** + * @brief 获取 IO 默认运行编号 + * + * @param handle 机械臂控制句柄 + * @param id IO 默认运行的在线编程文件编号,支持 0-100,0 代表无默认 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_default_run_program(rm_robot_handle *handle, int *id); +/** + * @brief 新增全局路点 + * + * @param handle 机械臂控制句柄 + * @param waypoint 新增全局路点参数(无需输入新增全局路点时间) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_add_global_waypoint(rm_robot_handle *handle, rm_waypoint_t waypoint); +/** + * @brief 更新全局路点 + * + * @param handle 机械臂控制句柄 + * @param waypoint 更新全局路点参数(无需输入更新全局路点时间) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_global_waypoint(rm_robot_handle *handle, rm_waypoint_t waypoint); +/** + * @brief 删除全局路点 + * + * @param handle 机械臂控制句柄 + * @param point_name 全局路点名称 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_global_waypoint(rm_robot_handle *handle, const char* point_name); +/** + * @brief 查询指定全局路点 + * + * @param handle 机械臂控制句柄 + * @param name 指定全局路点名称 + * @param point 返回指定的全局路点参数 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_global_waypoint(rm_robot_handle *handle, const char* name, rm_waypoint_t *point); +/** + * @brief 查询多个全局路点 + * + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param point_list 返回的全局路点列表 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_global_waypoints_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_waypoint_list_t *point_list); +/** @} */ // 结束在线编程组的定义 + +/** + * @defgroup UdpConfig UDP主动上报 + * + * 睿尔曼机械臂提供 UDP 机械臂状态主动上报接口,使用时,需要和机械臂处于同一局域网络下,通过设置主动上报配置接口的目标 IP或和机械臂建立 TCP 连接, + * 机械臂即会主动周期性上报机械臂状态数据,数据周期可配置,默认 5ms。配置正确并开启三线程模式后,通过注册回调函数可接收并处理主动上报数据。 + * @{ + */ +/** + * @brief 设置 UDP 机械臂状态主动上报配置 + * + * @param handle 机械臂控制句柄 + * @param config UDP配置结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_realtime_push(rm_robot_handle *handle, rm_realtime_push_config_t config); +/** + * @brief 查询 UDP 机械臂状态主动上报配置 + * + * @param handle 机械臂控制句柄 + * @param config 获取到的UDP机械臂状态主动上报配置 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_realtime_push(rm_robot_handle *handle, rm_realtime_push_config_t *config); +/** @} */ // 结束组的定义 + +/** + * @defgroup Electronic_Fence 电子围栏和虚拟墙 + * + * I 系列机械臂具备电子围栏与虚拟墙功能,并提供了针对控制器所保存的电子围栏或虚拟墙几何模型参数的操作接口。 + * 用户可以通过这些接口,实现对电子围栏或虚拟墙的新增、查询、更新和删除操作,在使用中,可以灵活地使用保存在 + * 控制器中的参数配置,需要注意的是,目前控制器支持保存的参数要求不超过10 个。 + * + * 电子围栏 + * 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动 + * 轨迹可能超出电子围栏的界限时,系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。 + * @attention 电子围栏目前仅支持长方体和点面矢量平面这两种形状,并且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境。 + * + * 虚拟墙 + * 虚拟墙功能支持在电流环拖动示教与力控拖动示教两种模式下,对拖动范围进行精确限制。在这两种特定的示教模式下,用户可以借助虚拟墙功能,确保 + * 机械臂的拖动操作不会超出预设的范围。 + * @attention 虚拟墙功能目前支持长方体和球体两种形状,并仅在上述两种示教模式下有效。在其他操作模式下,此功能将自动失效。因此,请确保在正确的操作模式 + * 下使用虚拟墙功能,以充分发挥其限制拖动范围的作用。 + * + * @{ + */ +/** + * @brief 新增几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config 几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 -4:form设置有误 + */ +RM_INTERFACE_EXPORT int rm_add_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 更新几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config 几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_update_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 删除指定几何模型 + * + * @param handle 机械臂控制句柄 + * @param form_name 几何模型名称,不超过 10 个字节,支持字母、数字、下划线 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_delete_electronic_fence_config(rm_robot_handle *handle, const char* form_name); +/** + * @brief 查询所有几何模型名称 + * + * @param handle 机械臂控制句柄 + * @param names 几何模型名称列表,长度为实际存在几何模型数量 + * @param len 几何模型名称列表长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_list_names(rm_robot_handle *handle, rm_fence_names_t *names, int *len); +/** + * @brief 查询指定几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param name 指定几何模型名称 + * @param config 返回几何模型参数结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_given_electronic_fence_config(rm_robot_handle *handle, const char* name, rm_fence_config_t *config); +/** + * @brief 查询所有几何模型参数 + * + * @param handle 机械臂控制句柄 + * @param config_list 几何模型信息列表,长度为实际存在几何模型数量 + * @param len 几何模型信息列表长度 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_list_infos(rm_robot_handle *handle, rm_fence_config_list_t *config_list, int *len); +/** + * @brief 设置电子围栏使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 电子围栏使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * @note 电子围栏功能通过精确设置参数,确保机械臂的轨迹规划、示教等运动均在设定的电子围栏范围内进行。当机械臂的运动轨迹可能超出电子围栏的界限时, + * 系统会立即返回相应的错误码,并自动中止运动,从而有效保障机械臂的安全运行。需要注意的是,电子围栏目前仅支持长方体和点面矢量平面这两种形状,并 + * 且其仅在仿真模式下生效,为用户提供一个预演轨迹与进行轨迹优化的安全环境 + */ +RM_INTERFACE_EXPORT int rm_set_electronic_fence_enable(rm_robot_handle *handle, rm_electronic_fence_enable_t state); +/** + * @brief 获取电子围栏使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 电子围栏使能状态 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_enable(rm_robot_handle *handle,rm_electronic_fence_enable_t *state); +/** + * @brief 设置当前电子围栏参数配置 + * + * @param handle 机械臂控制句柄 + * @param config 当前电子围栏参数结构体(无需设置电子围栏名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 获取当前电子围栏参数 + * + * @param handle 机械臂控制句柄 + * @param config 返回当前电子围栏参数结构体(返回参数中不包含电子围栏名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_electronic_fence_config(rm_robot_handle *handle, rm_fence_config_t *config); +/** + * @brief 设置虚拟墙使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 虚拟墙状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_virtual_wall_enable(rm_robot_handle *handle, rm_electronic_fence_enable_t state); +/** + * @brief 获取虚拟墙使能状态 + * + * @param handle 机械臂控制句柄 + * @param state 虚拟墙状态结构体 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_virtual_wall_enable(rm_robot_handle *handle,rm_electronic_fence_enable_t *state); +/** + * @brief 设置当前虚拟墙参数 + * + * @param handle 机械臂控制句柄 + * @param config 当前虚拟墙参数(无需设置虚拟墙名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_virtual_wall_config(rm_robot_handle *handle, rm_fence_config_t config); +/** + * @brief 获取当前虚拟墙参数 + * + * @param handle 机械臂控制句柄 + * @param config 当前虚拟墙参数(返回参数中不包含虚拟墙名称) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_virtual_wall_config(rm_robot_handle *handle, rm_fence_config_t *config); +/** @} */ // 结束电子围栏组的定义 + +/** + * @defgroup SelfCollision 自碰撞安全检测 + * + * 睿尔曼机械臂支持自碰撞安全检测,自碰撞安全检测使能状态下,可确保在轨迹规划、示教等运动过程中机械臂的各个部分不会相互碰撞。 + * @attention 以上自碰撞安全检测功能目前只在仿真模式下生效,用于进行预演轨迹与轨迹优化。 + * @{ + */ +/** + * @brief 设置自碰撞安全检测使能状态 + * + * @param handle 机械臂控制句柄 + * @param state true代表使能,false代表禁使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_set_self_collision_enable(rm_robot_handle *handle, bool state); +/** + * @brief 获取自碰撞安全检测使能状态 + * + * @param handle 机械臂控制句柄 + * @param state true代表使能,false代表禁使能 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + */ +RM_INTERFACE_EXPORT int rm_get_self_collision_enable(rm_robot_handle *handle,bool *state); +/** @} */ // 结束组的定义 + +/** + * @brief 设置末端生态协议模式 + * @param handle 机械臂控制句柄 + * @param mode 末端生态协议模式 + * 0:禁用协议 + * 9600:开启协议(波特率9600) + * 115200:开启协议(波特率115200) + * 256000:开启协议(波特率256000) + * 460800:开启协议(波特率460800) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_set_rm_plus_mode(rm_robot_handle *handle, int mode); + +/** + * @brief 查询末端生态协议模式 + * @param handle 机械臂控制句柄 + * @param mode 末端生态协议模式 + * 0:禁用协议 + * 9600:开启协议(波特率9600) + * 115200:开启协议(波特率115200) + * 256000:开启协议(波特率256000) + * 460800:开启协议(波特率460800) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_mode(rm_robot_handle *handle, int *mode); + +/** + * @brief 设置触觉传感器模式(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param mode 触觉传感器开关状态 0:关闭触觉传感器 1:打开触觉传感器(返回处理后数据) 2:打开触觉传感器(返回原始数据) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_set_rm_plus_touch(rm_robot_handle *handle, int mode); + +/** + * @brief 查询触觉传感器模式(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param mode 触觉传感器开关状态 0:关闭触觉传感器 1:打开触觉传感器(返回处理后数据) 2:打开触觉传感器(返回原始数据) + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_touch(rm_robot_handle *handle, int *mode); + +/** + * @brief 读取末端设备基础信息(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param info 末端设备基础信息 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_base_info(rm_robot_handle *handle, rm_plus_base_info_t *info); + +/** + * @brief 读取末端设备实时信息(末端生态协议支持) + * @param handle 机械臂控制句柄 + * @param info 末端设备实时信息 + * @return int 函数执行的状态码。 + - 0: 成功。 + - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + - -1: 数据发送失败,通信过程中出现问题。 + - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 +*/ +RM_INTERFACE_EXPORT int rm_get_rm_plus_state_info(rm_robot_handle *handle, rm_plus_state_info_t *info); + + + +/******************************************算法接口*******************************************************/ +/** + * @defgroup Algo 算法接口 + * + * 针对睿尔曼机械臂,提供正逆解、各种位姿参数转换等工具接口。 + * @{ + */ +/** + * @brief 查询算法库版本号 + * @return char* 返回版本号 + */ +RM_INTERFACE_EXPORT char* rm_algo_version(void); +/** + * @brief 初始化算法依赖数据(不连接机械臂时调用) + * + * @param Mode 机械臂型号 + * @param Type 传感器型号 + */ +RM_INTERFACE_EXPORT void rm_algo_init_sys_data(rm_robot_arm_model_e Mode, rm_force_type_e Type); +/** + * @brief 初始化算法依赖数据(不连接机械臂时调用) + * @details 初始化算法依赖数据,根据给定的DH参数判断机械臂类型,适用于通用型机械臂(RM_MODEL_UNIVERSAL_E)。 + * + * @param sensor_type 传感器型号 + * @param dh DH参数 + * @param dof 自由度 + */ +RM_INTERFACE_EXPORT void rm_algo_init_sys_data_by_dh(rm_force_type_e sensor_type, rm_dh_t dh, int dof); +/** + * @brief 设置算法机械臂自由度 + * @details 通用构型(RM_MODEL_UNIVERSAL_E)设置机器人自由度 + * + * @param dof 机械臂自由度 + */ +RM_INTERFACE_EXPORT void rm_algo_set_robot_dof(int dof); +/** + * @brief 设置安装角度 + * + * @param x X轴安装角度 单位° + * @param y Y轴安装角度 单位° + * @param z z轴安装角度 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_angle(float x, float y, float z); +/** + * @brief 获取安装角度 + * + * @param x X轴安装角度 单位° + * @param y Y轴安装角度 单位° + * @param z z轴安装角度 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_get_angle(float* x, float* y, float* z); +/** + * @brief 设置工作坐标系 + * + * @param coord_work 坐标系数据 + */ +RM_INTERFACE_EXPORT void rm_algo_set_workframe(const rm_frame_t* const coord_work); +/** + * @brief 获取当前工作坐标系 + * + * @param coord_work 当前工作坐标系 + */ +RM_INTERFACE_EXPORT void rm_algo_get_curr_workframe(rm_frame_t* coord_work); +/** + * @brief 设置工具坐标系 + * + * @param coord_tool 坐标系数据 + */ +RM_INTERFACE_EXPORT void rm_algo_set_toolframe(const rm_frame_t* const coord_tool); +/** + * @brief 获取当前工具坐标系 + * + * @param coord_tool 当前工具坐标系 + */ +RM_INTERFACE_EXPORT void rm_algo_get_curr_toolframe(rm_frame_t* coord_tool); +/** + * @brief 设置关节最大限位 + * + * @param joint_limit 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_limit(const float* const joint_limit); +/** + * @brief 获取关节最大限位 + * + * @param joint_limit 返回关节最大限位 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_limit(float* joint_limit); +/** + * @brief 设置关节最小限位 + * + * @param joint_limit 单位° + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_min_limit(const float* const joint_limit); +/** + * @brief 获取关节最小限位 + * + * @param joint_limit 返回关节最小限位 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_min_limit(float* joint_limit); +/** + * @brief 设置关节最大速度 + * + * @param joint_slim_max RPM + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_speed(const float* const joint_slim_max); +/** + * @brief 获取关节最大速度 + * + * @param joint_slim_max 返回关节最大速度 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_speed(float* joint_slim_max); +/** + * @brief 设置关节最大加速度 + * + * @param joint_alim_max RPM/s + */ +RM_INTERFACE_EXPORT void rm_algo_set_joint_max_acc(const float* const joint_alim_max); +/** + * @brief 获取关节最大加速度 + * + * @param joint_alim_max 返回关节最大加速度 + */ +RM_INTERFACE_EXPORT void rm_algo_get_joint_max_acc(float* joint_alim_max); +/** + * @brief 设置逆解求解模式 + * + * @param mode true:遍历模式,冗余参数遍历的求解策略。适于当前位姿跟要求解的位姿差别特别大的应用场景,如MOVJ_P、位姿编辑等,耗时较长 + false:单步模式,自动调整冗余参数的求解策略。适于当前位姿跟要求解的位姿差别特别小、连续周期控制的场景,如笛卡尔空间规划的位姿求解等,耗时短 + */ +RM_INTERFACE_EXPORT void rm_algo_set_redundant_parameter_traversal_mode(bool mode); +/** + * @brief 逆解函数,默认遍历模式,可使用Algo_Set_Redundant_Parameter_Traversal_Mode接口设置逆解求解模式 + * + * @param handle 机械臂控制句柄 + * @param params 逆解输入参数结构体 + * @param q_out 输出的关节角度 单位° + * @return int 逆解结果 + * - 0: 逆解成功 + * - 1: 逆解失败 + * - -1: 上一时刻关节角度输入为空 + * - -2: 目标位姿四元数不合法 + * @attention 机械臂已连接时,可直接调用该接口进行计算,计算使用的参数均为机械臂当前的参数; + * 未连接机械臂时,需首先调用初始化算法依赖数据接口,并按照实际需求设置使用的坐标系及关节速度位置等限制 + *(不设置则按照出厂默认的参数进行计算),此时机械臂控制句柄设置为NULL即可 + */ +RM_INTERFACE_EXPORT int rm_algo_inverse_kinematics(rm_robot_handle *handle, rm_inverse_kinematics_params_t params, float *q_out); + +/** + * @brief 计算逆运动学全解(当前仅支持六自由度机器人) + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param params 逆解输入参数结构体 + * @return rm_inverse_kinematics_all_solve_t 逆解的全解结构体 +*/ +RM_INTERFACE_EXPORT rm_inverse_kinematics_all_solve_t rm_algo_inverse_kinematics_all(rm_robot_handle *handle, rm_inverse_kinematics_params_t params); + +/** + * @brief 从多解中选取最优解(当前仅支持六自由度机器人) + * @param weight 权重,建议默认值为{1,1,1,1,1,1} + * @param params 待选解的全解结构体 + * @return int 最优解索引,选解结果为ik_solve.q_solve[i],如果没有合适的解返回-1(比如求出8组解,但是8组都有关节角度超限位,那么就返回-1) +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_select_ik_solve(float *weight, rm_inverse_kinematics_all_solve_t params); + + +/** + * @brief 检查逆解结果是否超出关节限位(当前仅支持六自由度机器人) + * @param q_solve 选解,单位:° + * @return int 0:未超限位,1~dof: 第i个关节超限位,-1:当前机器人非六自由度,当前仅支持六自由度机器人 +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_check_joint_position_limit(const float* const q_solve); + +/** + * @brief 检查逆解结果是否超速(当前仅支持六自由度机器人) + * @param dt 两帧数据之间的时间间隔,即控制周期,单位sec + * @param q_ref 参考关节角度或者第一帧数据角度,单位:° + * @param q_solve 求解结果,即下一帧要发送的角度 + * @return int 0:表示未超限 i:表示关节i超限,优先报序号小的关节 -1:当前机器人非六自由度,当前仅支持六自由度机器人 +*/ +RM_INTERFACE_EXPORT int rm_algo_ikine_check_joint_velocity_limit(float dt, const float* const q_ref, const float* const q_solve); + +/** + * @brief 根据参考位形计算臂角大小(仅支持RM75) + * @param q_ref 当前参考位形的关节角度,单位° + * @param arm_angle 计算结果,当前参考位形对应的臂角大小,单位° + * @return int + * 0: 求解成功 + * -1: 求解失败,或机型非RM75 + * -2: q_ref 输入参数非法 + */ +RM_INTERFACE_EXPORT int rm_algo_calculate_arm_angle_from_config_rm75(float *q_ref, float *arm_angle); + +/** + * @brief 臂角法求解RM75逆运动学 + * @param params rm_inverse_kinematics_params_t,逆解参数结构体 + * @param arm_angle 指定轴角大小,单位:° + * @param q_solve 求解结果,单位:° + * @return int + * 0: 求解成功 + * -1: 求解失败 + * -2: 求解结果超出限位 + * -3: 机型非RM75 + */ +RM_INTERFACE_EXPORT int rm_algo_inverse_kinematics_rm75_for_arm_angle(rm_inverse_kinematics_params_t params, float arm_angle, float *q_solve); + + + +/** + * @brief 通过分析雅可比矩阵最小奇异值, 判断机器人是否处于奇异状态 + * @param q 要判断的关节角度(机械零位描述),单位:° + * @param 最小奇异值阈值,若传NULL,则使用内部默认值,默认值为0.01(该值在0-1之间) + * @return 0:在当前阈值条件下正常 + * -1:表示在当前阈值条件下判断为奇异区 + * -2:表示计算失败 +*/ +RM_INTERFACE_EXPORT int rm_algo_universal_singularity_analyse(const float* const q, float singluar_value_limit); +/** + * @brief 恢复初始阈值(仅适用于解析法分析机器人奇异状态),阈值初始化为:limit_qe=10deg,limit_qw=10deg,limit_d = 0.05m +*/ +RM_INTERFACE_EXPORT void rm_algo_kin_singularity_thresholds_init(); + +/** + * @brief 设置自定义阈值(仅适用于解析法分析机器人奇异状态) + * @param limit_qe 肘部奇异区域范围设置(即J3接近0的范围),unit:°,default: about 10deg + * @param limit_qw 腕部奇异区域范围设置(即J5接近0的范围),unit:°,default: about 10deg + * @param limit_d 肩部奇异区域范围设置(即腕部中心点距离奇异平面的距离), unit: m, default: 0.05 +*/ +RM_INTERFACE_EXPORT void rm_algo_kin_set_singularity_thresholds(float limit_qe_algo, float limit_qw_algo, float limit_d_algo); + +/** + * @brief 获取自定义阈值(仅适用于解析法分析机器人奇异状态) + * + * @param limit_qe 肘部奇异区域范围获取(即J3接近0的范围), unit: °, default: about 10deg + * @param limit_qw 腕部奇异区域范围获取(即J5接近0的范围), unit: °, default: about 10deg + * @param limit_d 肩部奇异区域范围获取(即腕部中心点距离奇异平面的距离), unit: m, default: 0.05 + */ +RM_INTERFACE_EXPORT void rm_algo_kin_get_singularity_thresholds(float* limit_qe_algo, float* limit_qw_algo, float* limit_d_algo); + +/** + * @brief 解析法判断机器人是否处于奇异位形(仅支持六自由度) + * @param q 要判断的关节角度,单位:° + * @param distance 输出参数,返回腕部中心点到肩部奇异平面的距离,该值越接近0说明越接近肩部奇异,单位m,不需要时可传NULL + * @return 0表正常,-1表肩部奇异,-2表肘部奇异,-3表腕部奇异,-4仅支持6自由度机械臂 +*/ +RM_INTERFACE_EXPORT int rm_algo_kin_robot_singularity_analyse(const float* const q, float *distance); +/** + * @brief 设置工具包络球参数 + * @param toolSphere_i 工具包络球编号 (0~4) + * @param data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + */ +RM_INTERFACE_EXPORT void rm_algo_set_tool_envelope(const int toolSphere_i, rm_tool_sphere_t data); + +/** + * @brief 获取工具包络球参数 + * @param toolSphere_i 工具rm_get_tool_voltage包络球编号 (0~4) + * @param data 工具包络球参数,注意其参数在末端法兰坐标系下描述 + */ +RM_INTERFACE_EXPORT void rm_algo_get_tool_envelope(const int toolSphere_i, rm_tool_sphere_t *data); +/** + * @brief 自碰撞检测 + * @param joint 要判断的关节角度,单位:° + * @return int + * 0: 无碰撞 + * 1: 发生碰撞,超出关节限位将被认为发生碰撞 + */ +RM_INTERFACE_EXPORT int rm_algo_safety_robot_self_collision_detection(float *joint); +/** + * @brief 机械臂正解函数 + * + * @param handle 机械臂控制句柄 + * @param joint + * + * @return rm_pose_t 目标位姿 + * @attention 机械臂已连接时,可直接调用该接口进行计算,计算使用的参数均为机械臂当前的参数; + * 未连接机械臂时,需首先调用初始化算法依赖数据接口,并按照实际需求设置使用的坐标系及关节速度位置等限制 + *(不设置则按照出厂默认的参数进行计算),此时机械臂控制句柄设置为NULL即可 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_forward_kinematics(rm_robot_handle *handle,const float* const joint); +/** + * @brief 欧拉角转四元数 + * + * @param eu 欧拉角 + * @return rm_quat_t 四元数 + */ +RM_INTERFACE_EXPORT rm_quat_t rm_algo_euler2quaternion(rm_euler_t eu); +/** + * @brief 四元数转欧拉角 + * + * @param qua 四元数 + * @return rm_euler_t 欧拉角 + */ +RM_INTERFACE_EXPORT rm_euler_t rm_algo_quaternion2euler(rm_quat_t qua); +/** + * @brief 欧拉角转旋转矩阵 + * + * @param state 欧拉角 + * @return rm_matrix_t 旋转矩阵 + */ +RM_INTERFACE_EXPORT rm_matrix_t rm_algo_euler2matrix(rm_euler_t state); +/** + * @brief 位姿转旋转矩阵 + * + * @param state 位姿 + * @return rm_matrix_t 旋转矩阵 + */ +RM_INTERFACE_EXPORT rm_matrix_t rm_algo_pos2matrix(rm_pose_t state); +/** + * @brief 旋转矩阵转位姿 + * + * @param matrix 旋转矩阵 + * @return rm_pose_t 位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_matrix2pos(rm_matrix_t matrix); +/** + * @brief 基坐标系转工作坐标系 + * + * @param matrix 工作坐标系在基坐标系下的矩阵 + * @param state 工具端坐标在基坐标系下位姿 + * @return rm_pose_t 基坐标系在工作坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_base2workframe(rm_matrix_t matrix, rm_pose_t state); +/** + * @brief 工作坐标系转基坐标系 + * + * @param matrix 工作坐标系在基坐标系下的矩阵 + * @param state 工具端坐标在工作坐标系下位姿 + * @return rm_pose_t 工作坐标系在基坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_workframe2base(rm_matrix_t matrix, rm_pose_t state); +/** + * @brief 计算环绕运动位姿 + * + * @param handle 机械臂控制句柄 + * @param curr_joint 当前关节角度 单位° + * @param rotate_axis 旋转轴: 1:x轴, 2:y轴, 3:z轴 + * @param rotate_angle 旋转角度: 旋转角度, 单位(度) + * @param choose_axis 指定计算时使用的坐标系 + * @return rm_pose_t 计算位姿结果 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_rotate_move(rm_robot_handle *handle,const float* const curr_joint, int rotate_axis, float rotate_angle, rm_pose_t choose_axis); +/** + * @brief 计算沿工具坐标系运动位姿 + * + * @param handle 机械臂控制句柄 + * @param curr_joint 当前关节角度,单位:度 + * @param move_lengthx 沿X轴移动长度,单位:米 + * @param move_lengthy 沿Y轴移动长度,单位:米 + * @param move_lengthz 沿Z轴移动长度,单位:米 + * @return rm_pose_t 工作坐标系下的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_cartesian_tool(rm_robot_handle *handle,const float* const curr_joint, float move_lengthx, + float move_lengthy, float move_lengthz); + /** + * @brief 计算Pos和Rot沿某坐标系有一定的位移和旋转角度后,所得到的位姿数据 + * + * @param handle 机械臂控制句柄,连接机械臂时传入机械臂控制句柄,不连接时传入NULL + * @param poseCurrent 当前时刻位姿(欧拉角形式) + * @param deltaPosAndRot 移动及旋转数组,位置移动(单位:m),旋转(单位:度) + * @param frameMode 坐标系模式选择 0:Work(work即可任意设置坐标系),1:Tool + * @return rm_pose_t 平移旋转后的位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_pose_move(rm_robot_handle *handle,rm_pose_t poseCurrent, const float *deltaPosAndRot, int frameMode); +/** + * @brief 末端位姿转成工具位姿 + * + * @param handle 机械臂控制句柄 + * @param eu_end 基于世界坐标系和默认工具坐标系的末端位姿 + * @return rm_pose_t 基于工作坐标系和工具坐标系的末端位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_end2tool(rm_robot_handle *handle,rm_pose_t eu_end); +/** + * @brief 工具位姿转末端位姿 + * + * @param handle 机械臂控制句柄 + * @param eu_tool 基于工作坐标系和工具坐标系的末端位姿 + * @return rm_pose_t 基于世界坐标系和默认工具坐标系的末端位姿 + */ +RM_INTERFACE_EXPORT rm_pose_t rm_algo_tool2end(rm_robot_handle *handle,rm_pose_t eu_tool); +/** + * @brief 获取DH参数 + * + * @return rm_DH_t DH参数 + */ +RM_INTERFACE_EXPORT rm_dh_t rm_algo_get_dh(); +/** + * @brief 设置DH参数 + * + * @param dh DH参数 + */ +RM_INTERFACE_EXPORT void rm_algo_set_dh(rm_dh_t dh); +/** @} */ // 结束算法组的定义 + +/*********************************************四代控制器新增接口*******************************************************/ + +/** + * @brief 查询轨迹列表 + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param list 轨迹列表 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_trajectory_file_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_trajectory_list_t *trajectory_list); +/** + * @brief 开始运行指定轨迹 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_run_trajectory(rm_robot_handle *handle, const char *trajectory_name); +/** + * @brief 删除指定轨迹 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_delete_trajectory_file(rm_robot_handle *handle, const char *trajectory_name); +/** + * @brief 保存轨迹到控制器 + * @param handle 机械臂控制句柄 + * @param trajectory_name 轨迹名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_save_trajectory_file(rm_robot_handle *handle, const char *trajectory_name); + +/** + * @brief 设置机械臂急停状态 + * @param handle 机械臂控制句柄 + * @param state 急停状态,true:急停,false:恢复 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_arm_emergency_stop(rm_robot_handle *handle, bool state); +/** + * @brief 新增Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_add_modbus_tcp_master(rm_robot_handle *handle, rm_modbus_tcp_master_info_t master); +/** + * @brief 修改Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @param master 要修改的Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_update_modbus_tcp_master(rm_robot_handle *handle, const char *master_name, rm_modbus_tcp_master_info_t master); +/** + * @brief 删除Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_delete_modbus_tcp_master(rm_robot_handle *handle, const char *master_name); +/** + * @brief 查询Modbus TCP主站 + * @param handle 机械臂控制句柄 + * @param master_name Modbus TCP主站名称 + * @param master Modbus TCP主站信息 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_modbus_tcp_master(rm_robot_handle *handle, const char *master_name, rm_modbus_tcp_master_info_t *master); +/** + * @brief 查询TCP主站列表 + * @param handle 机械臂控制句柄 + * @param page_num 页码 + * @param page_size 每页大小 + * @param vague_search 模糊搜索 + * @param list TCP主站列表 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_modbus_tcp_master_list(rm_robot_handle *handle, int page_num, int page_size, const char *vague_search,rm_modbus_tcp_master_list_t *list); +/** + * @brief 设置控制器RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param controller_rs485_mode 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + * @param baudrate 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_controller_rs485_mode(rm_robot_handle *handle, int controller_rs485_mode, int baudrate); +/** + * @brief 查询控制器RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param controller_rs485_mode 0代表默认RS485串行通讯,1代表modbus-RTU主站模式,2-代表modbus-RTU从站模式。 + * @param baudrate 波特率(当前支持9600 19200 38400 57600 115200 230400 460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_controller_rs485_mode_v4(rm_robot_handle *handle, int *controller_rs485_mode, int *baudrate); +/** + * @brief 设置工具端RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param mode 通讯端口,0-设置工具端RS485端口为RTU主站,1-设置工具端RS485端口为灵巧手模式,2-设置工具端RS485端口为夹爪模式。 + * @param baudrate 波特率(当前支持9600,115200,460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_set_tool_rs485_mode(rm_robot_handle *handle, int mode, int baudrate); +/** + * @brief 查询工具端RS485模式(四代控制器支持) + * @param handle 机械臂控制句柄 + * @param tool_rs485_mode 0-代表modbus-RTU主站模式,1-代表灵巧手模式,2-代表夹爪模式。 + * @param baudrate 波特率(当前支持9600,115200,460800) + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_get_tool_rs485_mode_v4(rm_robot_handle *handle, int *tool_rs485_mode, int *baudrate); +/** + * @brief Modbus RTU协议读线圈 + * @param handle 机械臂控制句柄 + * @param param 读线圈参数 + * @param data 读线圈数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_coils(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议写线圈 + * @param handle 机械臂控制句柄 + * @param param 写线圈参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_rtu_coils(rm_robot_handle *handle, rm_modbus_rtu_write_params_t param); +/** + * @brief Modbus RTU协议读离散量输入 + * @param handle 机械臂控制句柄 + * @param param 读离散输入参数 + * @param data 读离散输入数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_input_status(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议读保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 读保持寄存器参数 + * @param data 读保持寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_holding_registers(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus RTU协议写保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 写保持寄存器参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_rtu_registers(rm_robot_handle *handle, rm_modbus_rtu_write_params_t param); +/** + * @brief Modbus RTU协议读输入寄存器 + * @param handle 机械臂控制句柄 + * @param param 读输入寄存器参数 + * @param data 读输入寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_rtu_input_registers(rm_robot_handle *handle, rm_modbus_rtu_read_params_t param, int *data); +/** + * @brief Modbus TCP协议读线圈 + * @param handle 机械臂控制句柄 + * @param param 读线圈参数 + * @param data 读线圈数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_coils(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议写线圈 + * @param handle 机械臂控制句柄 + * @param param 写线圈参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_tcp_coils(rm_robot_handle *handle, rm_modbus_tcp_write_params_t param); +/** + * @brief Modbus TCP协议读离散量输入 + * @param handle 机械臂控制句柄 + * @param param 读离散输入参数 + * @param data 读离散输入数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_input_status(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议读保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 读保持寄存器参数 + * @param data 读保持寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_holding_registers(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); +/** + * @brief Modbus TCP协议写保持寄存器 + * @param handle 机械臂控制句柄 + * @param param 写保持寄存器参数 + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_write_modbus_tcp_registers(rm_robot_handle *handle, rm_modbus_tcp_write_params_t param); +/** + * @brief Modbus TCP协议读输入寄存器 + * @param handle 机械臂控制句柄 + * @param param 读输入寄存器参数 + * @param data 读输入寄存器数据,数组大小为param.num + * @return int 函数执行的状态码。 + * - 0: 成功。 + * - 1: 控制器返回false,传递参数错误或机械臂状态发生错误。 + * - -1: 数据发送失败,通信过程中出现问题。 + * - -2: 数据接收失败,通信过程中出现问题或者控制器超时没有返回。 + * - -3: 返回值解析失败,接收到的数据格式不正确或不完整。 + * - -4: 三代控制器不支持该接口。 + */ +RM_INTERFACE_EXPORT int rm_read_modbus_tcp_input_registers(rm_robot_handle *handle, rm_modbus_tcp_read_params_t param, int *data); + + +}; + +#endif // __cplusplus + +#endif // MY_CPP_WRAPPER_H \ No newline at end of file diff --git a/include/rm_version.h b/include/rm_version.h new file mode 100644 index 0000000..b6fdfc1 --- /dev/null +++ b/include/rm_version.h @@ -0,0 +1,16 @@ + +#ifndef RM_VERSION_H +#define RM_VERSION_H + +#ifdef __cplusplus +extern "C" { +#endif + +#define SDK_VERSION ("1.1.1") + +#ifdef __cplusplus +} +#endif + +#endif + \ No newline at end of file diff --git a/lib/api_cpp.dll b/lib/api_cpp.dll new file mode 100644 index 0000000..187a1d6 Binary files /dev/null and b/lib/api_cpp.dll differ diff --git a/lib/api_cpp.lib b/lib/api_cpp.lib new file mode 100644 index 0000000..9af3973 Binary files /dev/null and b/lib/api_cpp.lib differ diff --git a/lib/libapi_cpp.so b/lib/libapi_cpp.so new file mode 100644 index 0000000..aa36d5e Binary files /dev/null and b/lib/libapi_cpp.so differ diff --git a/rm_arm_control/CMakeLists.txt b/rm_arm_control/CMakeLists.txt new file mode 100644 index 0000000..41b9aa0 --- /dev/null +++ b/rm_arm_control/CMakeLists.txt @@ -0,0 +1,118 @@ +cmake_minimum_required(VERSION 3.10) +project(rm_arm_control) + +# 设置 C 标准 +set(CMAKE_C_STANDARD 11) + +# 添加忽略定义重定义警告的选项 +if(CMAKE_C_COMPILER_ID STREQUAL "GNU" OR CMAKE_C_COMPILER_ID STREQUAL "Clang") + add_compile_options(-Wno-define-redefinition) +endif() +add_compile_options(-g) + +set(ROS_DOMAIN_ID_STR $ENV{ROS_DOMAIN_ID}) +if(NOT ROS_DOMAIN_ID_STR) + set(ROS_DOMAIN_ID_STR "0") # 未设置时默认 0 +endif() + +# 2. 验证是否为非负整数(用正则表达式) +if(ROS_DOMAIN_ID_STR MATCHES "^[0-9]+$") + # 是有效整数,转换为数字(用 math 命令) + math(EXPR DOMAIN_ID_NUM "${ROS_DOMAIN_ID_STR}") +else() + # 无效值,警告并使用默认 0 + message(WARNING "Invalid ROS_DOMAIN_ID (${ROS_DOMAIN_ID_STR}), using default 0") + set(DOMAIN_ID_NUM 0) +endif() + +# 3. 根据域 ID 判断环境 +if(DOMAIN_ID_NUM EQUAL 10) + message(STATUS "Detected simulation environment (ROS_DOMAIN_ID=10)") + add_compile_definitions(SIMULATION) # 模拟环境宏 +else() + message(STATUS "Detected real robot environment (ROS_DOMAIN_ID=${DOMAIN_ID_NUM})") + add_compile_definitions(REAL_ROBOT) # 实机环境宏 +endif() + +# 依赖 +find_package(ament_cmake REQUIRED) +find_package(Eigen3 REQUIRED) # 查找Eigen3库 +find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(trajectory_msgs REQUIRED) +find_package(control_msgs REQUIRED) +find_package(gjk_interface REQUIRED) +find_package(interfaces REQUIRED) +find_package(moveit_core REQUIRED) +find_package(moveit_ros_planning_interface REQUIRED) + +include_directories( + include + ${CMAKE_CURRENT_SOURCE_DIR}/../include + ${EIGEN3_INCLUDE_DIRS} # 引入Eigen3的头文件路径 +) + + +# 设置源文件 +set(SOURCES + src/rm_arm_handler.cpp + src/rm_arm_node.cpp + simulator/rm_arm_simulator.cpp + simulator/trapezoidal_trajectory_kinematics.cpp + simulator/rm_driver_kinematics.cpp + src/goal_manager.cpp + driver/arm_driver.cpp + driver/rm_arm_driver.cpp + src/main.cpp + src/init_set.cpp +) + +# 添加可执行文件 +add_executable(rm_arm_control ${SOURCES}) + +ament_target_dependencies(rm_arm_control + rclcpp + rclcpp_action + geometry_msgs + sensor_msgs + trajectory_msgs + control_msgs + gjk_interface + interfaces + moveit_core + moveit_ros_planning_interface +) + +# 查找库 +find_library(RMAN_API_LIB NAMES api_cpp PATHS "${CMAKE_CURRENT_SOURCE_DIR}/Robotic_Arm/lib") + +# 链接库 +target_link_libraries(rm_arm_control ${RMAN_API_LIB}) + +# 如果是 UNIX 平台且不是 ARM 平台,确保动态库文件可以在运行时被找到(这一步通常不是必须的,但在某些配置下可能需要) +if(UNIX) + add_custom_command(TARGET rm_arm_control POST_BUILD + COMMAND ${CMAKE_COMMAND} -E copy_if_different + "${CMAKE_CURRENT_SOURCE_DIR}/Robotic_Arm/lib/libapi_cpp.so" + $) +endif() + +install(TARGETS + rm_arm_control + DESTINATION lib/${PROJECT_NAME}) + +# 安装第三方库到安装目录(重要) +install(DIRECTORY + ${CMAKE_CURRENT_SOURCE_DIR}/Robotic_Arm/lib + DESTINATION lib/.. + FILES_MATCHING PATTERN "*.so*" +) + +install( + DIRECTORY launch urdf meshes # 安装 launch、urdf、meshes 目录 + DESTINATION share/${PROJECT_NAME} +) + +ament_package() diff --git a/rm_arm_control/LICENSE b/rm_arm_control/LICENSE new file mode 100644 index 0000000..0ef8650 --- /dev/null +++ b/rm_arm_control/LICENSE @@ -0,0 +1,13 @@ +Copyright 2024 realman-robotics + +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. diff --git a/rm_arm_control/Robotic_Arm/lib/api_cpp.dll b/rm_arm_control/Robotic_Arm/lib/api_cpp.dll new file mode 100644 index 0000000..187a1d6 Binary files /dev/null and b/rm_arm_control/Robotic_Arm/lib/api_cpp.dll differ diff --git a/rm_arm_control/Robotic_Arm/lib/api_cpp.lib b/rm_arm_control/Robotic_Arm/lib/api_cpp.lib new file mode 100644 index 0000000..9af3973 Binary files /dev/null and b/rm_arm_control/Robotic_Arm/lib/api_cpp.lib differ diff --git a/rm_arm_control/Robotic_Arm/lib/libapi_cpp.so b/rm_arm_control/Robotic_Arm/lib/libapi_cpp.so new file mode 100644 index 0000000..aa36d5e Binary files /dev/null and b/rm_arm_control/Robotic_Arm/lib/libapi_cpp.so differ diff --git a/rm_arm_control/build/CMakeCache.txt b/rm_arm_control/build/CMakeCache.txt new file mode 100644 index 0000000..85f6c28 --- /dev/null +++ b/rm_arm_control/build/CMakeCache.txt @@ -0,0 +1,712 @@ +# This is the CMakeCache file. +# For build in directory: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build +# It was generated by CMake: /usr/bin/cmake +# You can edit this file to change values found and used by cmake. +# If you do not want to change any of the values, simply exit the editor. +# If you do want to change a value, simply edit, save, and exit the editor. +# The syntax for the file is as follows: +# KEY:TYPE=VALUE +# KEY is the name of a variable in the cache. +# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!. +# VALUE is the current value for the KEY. + +######################## +# EXTERNAL cache entries +######################## + +//Generate environment files in the CMAKE_INSTALL_PREFIX +AMENT_CMAKE_ENVIRONMENT_GENERATION:BOOL=OFF + +//Generate environment files in the package share folder +AMENT_CMAKE_ENVIRONMENT_PACKAGE_GENERATION:BOOL=ON + +//Generate marker file containing the parent prefix path +AMENT_CMAKE_ENVIRONMENT_PARENT_PREFIX_PATH_GENERATION:BOOL=ON + +//Replace the CMake install command with a custom implementation +// using symlinks instead of copying resources +AMENT_CMAKE_SYMLINK_INSTALL:BOOL=OFF + +//Generate an uninstall target to revert the effects of the install +// step +AMENT_CMAKE_UNINSTALL_TARGET:BOOL=ON + +//The path where test results are generated +AMENT_TEST_RESULTS_DIR:PATH=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/test_results + +//Build the testing tree. +BUILD_TESTING:BOOL=ON + +//Path to a program. +CMAKE_ADDR2LINE:FILEPATH=/usr/bin/addr2line + +//Path to a program. +CMAKE_AR:FILEPATH=/usr/bin/ar + +//Choose the type of build, options are: None Debug Release RelWithDebInfo +// MinSizeRel ... +CMAKE_BUILD_TYPE:STRING= + +//Enable/Disable color output during build. +CMAKE_COLOR_MAKEFILE:BOOL=ON + +//CXX compiler +CMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++ + +//A wrapper around 'ar' adding the appropriate '--plugin' option +// for the GCC compiler +CMAKE_CXX_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-11 + +//A wrapper around 'ranlib' adding the appropriate '--plugin' option +// for the GCC compiler +CMAKE_CXX_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-11 + +//Flags used by the CXX compiler during all build types. +CMAKE_CXX_FLAGS:STRING= + +//Flags used by the CXX compiler during DEBUG builds. +CMAKE_CXX_FLAGS_DEBUG:STRING=-g + +//Flags used by the CXX compiler during MINSIZEREL builds. +CMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the CXX compiler during RELEASE builds. +CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the CXX compiler during RELWITHDEBINFO builds. +CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//C compiler +CMAKE_C_COMPILER:FILEPATH=/usr/bin/cc + +//A wrapper around 'ar' adding the appropriate '--plugin' option +// for the GCC compiler +CMAKE_C_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-11 + +//A wrapper around 'ranlib' adding the appropriate '--plugin' option +// for the GCC compiler +CMAKE_C_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-11 + +//Flags used by the C compiler during all build types. +CMAKE_C_FLAGS:STRING= + +//Flags used by the C compiler during DEBUG builds. +CMAKE_C_FLAGS_DEBUG:STRING=-g + +//Flags used by the C compiler during MINSIZEREL builds. +CMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG + +//Flags used by the C compiler during RELEASE builds. +CMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG + +//Flags used by the C compiler during RELWITHDEBINFO builds. +CMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG + +//Path to a program. +CMAKE_DLLTOOL:FILEPATH=CMAKE_DLLTOOL-NOTFOUND + +//Flags used by the linker during all build types. +CMAKE_EXE_LINKER_FLAGS:STRING= + +//Flags used by the linker during DEBUG builds. +CMAKE_EXE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during MINSIZEREL builds. +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during RELEASE builds. +CMAKE_EXE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during RELWITHDEBINFO builds. +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Enable/Disable output of compile commands during generation. +CMAKE_EXPORT_COMPILE_COMMANDS:BOOL= + +//Install path prefix, prepended onto install directories. +CMAKE_INSTALL_PREFIX:PATH=/usr/local + +//Path to a program. +CMAKE_LINKER:FILEPATH=/usr/bin/ld + +//Path to a program. +CMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/gmake + +//Flags used by the linker during the creation of modules during +// all build types. +CMAKE_MODULE_LINKER_FLAGS:STRING= + +//Flags used by the linker during the creation of modules during +// DEBUG builds. +CMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during the creation of modules during +// MINSIZEREL builds. +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during the creation of modules during +// RELEASE builds. +CMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during the creation of modules during +// RELWITHDEBINFO builds. +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_NM:FILEPATH=/usr/bin/nm + +//Path to a program. +CMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy + +//Path to a program. +CMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump + +//Value Computed by CMake +CMAKE_PROJECT_DESCRIPTION:STATIC= + +//Value Computed by CMake +CMAKE_PROJECT_HOMEPAGE_URL:STATIC= + +//Value Computed by CMake +CMAKE_PROJECT_NAME:STATIC=rm_arm_control + +//Path to a program. +CMAKE_RANLIB:FILEPATH=/usr/bin/ranlib + +//Path to a program. +CMAKE_READELF:FILEPATH=/usr/bin/readelf + +//Flags used by the linker during the creation of shared libraries +// during all build types. +CMAKE_SHARED_LINKER_FLAGS:STRING= + +//Flags used by the linker during the creation of shared libraries +// during DEBUG builds. +CMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during the creation of shared libraries +// during MINSIZEREL builds. +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during the creation of shared libraries +// during RELEASE builds. +CMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during the creation of shared libraries +// during RELWITHDEBINFO builds. +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//If set, runtime paths are not added when installing shared libraries, +// but are added when building. +CMAKE_SKIP_INSTALL_RPATH:BOOL=NO + +//If set, runtime paths are not added when using shared libraries. +CMAKE_SKIP_RPATH:BOOL=NO + +//Flags used by the linker during the creation of static libraries +// during all build types. +CMAKE_STATIC_LINKER_FLAGS:STRING= + +//Flags used by the linker during the creation of static libraries +// during DEBUG builds. +CMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING= + +//Flags used by the linker during the creation of static libraries +// during MINSIZEREL builds. +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING= + +//Flags used by the linker during the creation of static libraries +// during RELEASE builds. +CMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING= + +//Flags used by the linker during the creation of static libraries +// during RELWITHDEBINFO builds. +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING= + +//Path to a program. +CMAKE_STRIP:FILEPATH=/usr/bin/strip + +//If this value is on, makefiles will be generated without the +// .SILENT directive, and all commands will be echoed to the console +// during the make. This is useful for debugging only. With Visual +// Studio IDE projects all commands are done without /nologo. +CMAKE_VERBOSE_MAKEFILE:BOOL=FALSE + +//The directory containing a CMake configuration file for Eigen3. +Eigen3_DIR:PATH=/usr/share/eigen3/cmake + +//Path to a library. +FastCDR_LIBRARY_DEBUG:FILEPATH=FastCDR_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +FastCDR_LIBRARY_RELEASE:FILEPATH=/opt/ros/humble/lib/libfastcdr.so + +//Path to a file. +FastRTPS_INCLUDE_DIR:PATH=/opt/ros/humble/include + +//Path to a library. +FastRTPS_LIBRARY_DEBUG:FILEPATH=FastRTPS_LIBRARY_DEBUG-NOTFOUND + +//Path to a library. +FastRTPS_LIBRARY_RELEASE:FILEPATH=/opt/ros/humble/lib/libfastrtps.so + +//Path to a library. +OPENSSL_CRYPTO_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/libcrypto.so + +//Path to a file. +OPENSSL_INCLUDE_DIR:PATH=/usr/include + +//Path to a library. +OPENSSL_SSL_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/libssl.so + +//Arguments to supply to pkg-config +PKG_CONFIG_ARGN:STRING= + +//pkg-config executable +PKG_CONFIG_EXECUTABLE:FILEPATH=/usr/bin/pkg-config + +//Path to a program. +Python3_EXECUTABLE:FILEPATH=/usr/bin/python3 + +//Path to a library. +RMAN_API_LIB:FILEPATH=/home/zj/hivecore_robot_os/HiveCoreR1/lib/libapi_cpp.so + +//Name of the computer/site where compile is being run +SITE:STRING=zj-OMEN-Gaming-Laptop-16-am0xxx + +//The directory containing a CMake configuration file for TinyXML2. +TinyXML2_DIR:PATH=TinyXML2_DIR-NOTFOUND + +//Path to a library. +_lib:FILEPATH=/opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_fastrtps_cpp.so + +//The directory containing a CMake configuration file for action_msgs. +action_msgs_DIR:PATH=/opt/ros/humble/share/action_msgs/cmake + +//The directory containing a CMake configuration file for ament_cmake. +ament_cmake_DIR:PATH=/opt/ros/humble/share/ament_cmake/cmake + +//The directory containing a CMake configuration file for ament_cmake_core. +ament_cmake_core_DIR:PATH=/opt/ros/humble/share/ament_cmake_core/cmake + +//The directory containing a CMake configuration file for ament_cmake_export_definitions. +ament_cmake_export_definitions_DIR:PATH=/opt/ros/humble/share/ament_cmake_export_definitions/cmake + +//The directory containing a CMake configuration file for ament_cmake_export_dependencies. +ament_cmake_export_dependencies_DIR:PATH=/opt/ros/humble/share/ament_cmake_export_dependencies/cmake + +//The directory containing a CMake configuration file for ament_cmake_export_include_directories. +ament_cmake_export_include_directories_DIR:PATH=/opt/ros/humble/share/ament_cmake_export_include_directories/cmake + +//The directory containing a CMake configuration file for ament_cmake_export_interfaces. +ament_cmake_export_interfaces_DIR:PATH=/opt/ros/humble/share/ament_cmake_export_interfaces/cmake + +//The directory containing a CMake configuration file for ament_cmake_export_libraries. +ament_cmake_export_libraries_DIR:PATH=/opt/ros/humble/share/ament_cmake_export_libraries/cmake + +//The directory containing a CMake configuration file for ament_cmake_export_link_flags. +ament_cmake_export_link_flags_DIR:PATH=/opt/ros/humble/share/ament_cmake_export_link_flags/cmake + +//The directory containing a CMake configuration file for ament_cmake_export_targets. +ament_cmake_export_targets_DIR:PATH=/opt/ros/humble/share/ament_cmake_export_targets/cmake + +//The directory containing a CMake configuration file for ament_cmake_gen_version_h. +ament_cmake_gen_version_h_DIR:PATH=/opt/ros/humble/share/ament_cmake_gen_version_h/cmake + +//The directory containing a CMake configuration file for ament_cmake_include_directories. +ament_cmake_include_directories_DIR:PATH=/opt/ros/humble/share/ament_cmake_include_directories/cmake + +//The directory containing a CMake configuration file for ament_cmake_libraries. +ament_cmake_libraries_DIR:PATH=/opt/ros/humble/share/ament_cmake_libraries/cmake + +//The directory containing a CMake configuration file for ament_cmake_python. +ament_cmake_python_DIR:PATH=/opt/ros/humble/share/ament_cmake_python/cmake + +//The directory containing a CMake configuration file for ament_cmake_target_dependencies. +ament_cmake_target_dependencies_DIR:PATH=/opt/ros/humble/share/ament_cmake_target_dependencies/cmake + +//The directory containing a CMake configuration file for ament_cmake_test. +ament_cmake_test_DIR:PATH=/opt/ros/humble/share/ament_cmake_test/cmake + +//The directory containing a CMake configuration file for ament_cmake_version. +ament_cmake_version_DIR:PATH=/opt/ros/humble/share/ament_cmake_version/cmake + +//The directory containing a CMake configuration file for ament_index_cpp. +ament_index_cpp_DIR:PATH=/opt/ros/humble/share/ament_index_cpp/cmake + +//The directory containing a CMake configuration file for builtin_interfaces. +builtin_interfaces_DIR:PATH=/opt/ros/humble/share/builtin_interfaces/cmake + +//The directory containing a CMake configuration file for control_msgs. +control_msgs_DIR:PATH=/opt/ros/humble/share/control_msgs/cmake + +//The directory containing a CMake configuration file for fastcdr. +fastcdr_DIR:PATH=/opt/ros/humble/lib/cmake/fastcdr + +//The directory containing a CMake configuration file for fastrtps. +fastrtps_DIR:PATH=/opt/ros/humble/share/fastrtps/cmake + +//The directory containing a CMake configuration file for fastrtps_cmake_module. +fastrtps_cmake_module_DIR:PATH=/opt/ros/humble/share/fastrtps_cmake_module/cmake + +//The directory containing a CMake configuration file for fmt. +fmt_DIR:PATH=/usr/lib/x86_64-linux-gnu/cmake/fmt + +//The directory containing a CMake configuration file for foonathan_memory. +foonathan_memory_DIR:PATH=/opt/ros/humble/lib/foonathan_memory/cmake + +//The directory containing a CMake configuration file for geometry_msgs. +geometry_msgs_DIR:PATH=/opt/ros/humble/share/geometry_msgs/cmake + +//The directory containing a CMake configuration file for libstatistics_collector. +libstatistics_collector_DIR:PATH=/opt/ros/humble/share/libstatistics_collector/cmake + +//The directory containing a CMake configuration file for libyaml_vendor. +libyaml_vendor_DIR:PATH=/opt/ros/humble/share/libyaml_vendor/cmake + +//Path to a library. +pkgcfg_lib__OPENSSL_crypto:FILEPATH=/usr/lib/x86_64-linux-gnu/libcrypto.so + +//Path to a library. +pkgcfg_lib__OPENSSL_ssl:FILEPATH=/usr/lib/x86_64-linux-gnu/libssl.so + +//The directory containing a CMake configuration file for rcl. +rcl_DIR:PATH=/opt/ros/humble/share/rcl/cmake + +//The directory containing a CMake configuration file for rcl_interfaces. +rcl_interfaces_DIR:PATH=/opt/ros/humble/share/rcl_interfaces/cmake + +//The directory containing a CMake configuration file for rcl_logging_interface. +rcl_logging_interface_DIR:PATH=/opt/ros/humble/share/rcl_logging_interface/cmake + +//The directory containing a CMake configuration file for rcl_logging_spdlog. +rcl_logging_spdlog_DIR:PATH=/opt/ros/humble/share/rcl_logging_spdlog/cmake + +//The directory containing a CMake configuration file for rcl_yaml_param_parser. +rcl_yaml_param_parser_DIR:PATH=/opt/ros/humble/share/rcl_yaml_param_parser/cmake + +//The directory containing a CMake configuration file for rclcpp. +rclcpp_DIR:PATH=/opt/ros/humble/share/rclcpp/cmake + +//The directory containing a CMake configuration file for rcpputils. +rcpputils_DIR:PATH=/opt/ros/humble/share/rcpputils/cmake + +//The directory containing a CMake configuration file for rcutils. +rcutils_DIR:PATH=/opt/ros/humble/share/rcutils/cmake + +//Value Computed by CMake +rm_arm_control_BINARY_DIR:STATIC=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build + +//Value Computed by CMake +rm_arm_control_IS_TOP_LEVEL:STATIC=ON + +//Value Computed by CMake +rm_arm_control_SOURCE_DIR:STATIC=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control + +//The directory containing a CMake configuration file for rmw. +rmw_DIR:PATH=/opt/ros/humble/share/rmw/cmake + +//The directory containing a CMake configuration file for rmw_dds_common. +rmw_dds_common_DIR:PATH=/opt/ros/humble/share/rmw_dds_common/cmake + +//The directory containing a CMake configuration file for rmw_fastrtps_cpp. +rmw_fastrtps_cpp_DIR:PATH=/opt/ros/humble/share/rmw_fastrtps_cpp/cmake + +//The directory containing a CMake configuration file for rmw_fastrtps_shared_cpp. +rmw_fastrtps_shared_cpp_DIR:PATH=/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake + +//The directory containing a CMake configuration file for rmw_implementation. +rmw_implementation_DIR:PATH=/opt/ros/humble/share/rmw_implementation/cmake + +//The directory containing a CMake configuration file for rmw_implementation_cmake. +rmw_implementation_cmake_DIR:PATH=/opt/ros/humble/share/rmw_implementation_cmake/cmake + +//The directory containing a CMake configuration file for rosgraph_msgs. +rosgraph_msgs_DIR:PATH=/opt/ros/humble/share/rosgraph_msgs/cmake + +//The directory containing a CMake configuration file for rosidl_adapter. +rosidl_adapter_DIR:PATH=/opt/ros/humble/share/rosidl_adapter/cmake + +//The directory containing a CMake configuration file for rosidl_cmake. +rosidl_cmake_DIR:PATH=/opt/ros/humble/share/rosidl_cmake/cmake + +//The directory containing a CMake configuration file for rosidl_default_runtime. +rosidl_default_runtime_DIR:PATH=/opt/ros/humble/share/rosidl_default_runtime/cmake + +//The directory containing a CMake configuration file for rosidl_generator_c. +rosidl_generator_c_DIR:PATH=/opt/ros/humble/share/rosidl_generator_c/cmake + +//The directory containing a CMake configuration file for rosidl_generator_cpp. +rosidl_generator_cpp_DIR:PATH=/opt/ros/humble/share/rosidl_generator_cpp/cmake + +//The directory containing a CMake configuration file for rosidl_runtime_c. +rosidl_runtime_c_DIR:PATH=/opt/ros/humble/share/rosidl_runtime_c/cmake + +//The directory containing a CMake configuration file for rosidl_runtime_cpp. +rosidl_runtime_cpp_DIR:PATH=/opt/ros/humble/share/rosidl_runtime_cpp/cmake + +//The directory containing a CMake configuration file for rosidl_typesupport_c. +rosidl_typesupport_c_DIR:PATH=/opt/ros/humble/share/rosidl_typesupport_c/cmake + +//The directory containing a CMake configuration file for rosidl_typesupport_cpp. +rosidl_typesupport_cpp_DIR:PATH=/opt/ros/humble/share/rosidl_typesupport_cpp/cmake + +//The directory containing a CMake configuration file for rosidl_typesupport_fastrtps_c. +rosidl_typesupport_fastrtps_c_DIR:PATH=/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake + +//The directory containing a CMake configuration file for rosidl_typesupport_fastrtps_cpp. +rosidl_typesupport_fastrtps_cpp_DIR:PATH=/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake + +//The directory containing a CMake configuration file for rosidl_typesupport_interface. +rosidl_typesupport_interface_DIR:PATH=/opt/ros/humble/share/rosidl_typesupport_interface/cmake + +//The directory containing a CMake configuration file for rosidl_typesupport_introspection_c. +rosidl_typesupport_introspection_c_DIR:PATH=/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake + +//The directory containing a CMake configuration file for rosidl_typesupport_introspection_cpp. +rosidl_typesupport_introspection_cpp_DIR:PATH=/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake + +//The directory containing a CMake configuration file for sensor_msgs. +sensor_msgs_DIR:PATH=/opt/ros/humble/share/sensor_msgs/cmake + +//The directory containing a CMake configuration file for spdlog. +spdlog_DIR:PATH=/usr/lib/x86_64-linux-gnu/cmake/spdlog + +//The directory containing a CMake configuration file for spdlog_vendor. +spdlog_vendor_DIR:PATH=/opt/ros/humble/share/spdlog_vendor/cmake + +//The directory containing a CMake configuration file for statistics_msgs. +statistics_msgs_DIR:PATH=/opt/ros/humble/share/statistics_msgs/cmake + +//The directory containing a CMake configuration file for std_msgs. +std_msgs_DIR:PATH=/opt/ros/humble/share/std_msgs/cmake + +//The directory containing a CMake configuration file for tracetools. +tracetools_DIR:PATH=/opt/ros/humble/share/tracetools/cmake + +//The directory containing a CMake configuration file for trajectory_msgs. +trajectory_msgs_DIR:PATH=/opt/ros/humble/share/trajectory_msgs/cmake + +//The directory containing a CMake configuration file for unique_identifier_msgs. +unique_identifier_msgs_DIR:PATH=/opt/ros/humble/share/unique_identifier_msgs/cmake + +//The directory containing a CMake configuration file for yaml. +yaml_DIR:PATH=/opt/ros/humble/cmake + + +######################## +# INTERNAL cache entries +######################## + +//ADVANCED property for variable: CMAKE_ADDR2LINE +CMAKE_ADDR2LINE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_AR +CMAKE_AR-ADVANCED:INTERNAL=1 +//This is the directory where this CMakeCache.txt was created +CMAKE_CACHEFILE_DIR:INTERNAL=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build +//Major version of cmake used to create the current loaded cache +CMAKE_CACHE_MAJOR_VERSION:INTERNAL=3 +//Minor version of cmake used to create the current loaded cache +CMAKE_CACHE_MINOR_VERSION:INTERNAL=22 +//Patch version of cmake used to create the current loaded cache +CMAKE_CACHE_PATCH_VERSION:INTERNAL=1 +//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE +CMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1 +//Path to CMake executable. +CMAKE_COMMAND:INTERNAL=/usr/bin/cmake +//Path to cpack program executable. +CMAKE_CPACK_COMMAND:INTERNAL=/usr/bin/cpack +//Path to ctest program executable. +CMAKE_CTEST_COMMAND:INTERNAL=/usr/bin/ctest +//ADVANCED property for variable: CMAKE_CXX_COMPILER +CMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_COMPILER_AR +CMAKE_CXX_COMPILER_AR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_COMPILER_RANLIB +CMAKE_CXX_COMPILER_RANLIB-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS +CMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG +CMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL +CMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE +CMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO +CMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_COMPILER +CMAKE_C_COMPILER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_COMPILER_AR +CMAKE_C_COMPILER_AR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_COMPILER_RANLIB +CMAKE_C_COMPILER_RANLIB-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS +CMAKE_C_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG +CMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL +CMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE +CMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO +CMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_DLLTOOL +CMAKE_DLLTOOL-ADVANCED:INTERNAL=1 +//Executable file format +CMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS +CMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG +CMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL +CMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE +CMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS +CMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1 +//Name of external makefile project generator. +CMAKE_EXTRA_GENERATOR:INTERNAL= +//Name of generator. +CMAKE_GENERATOR:INTERNAL=Unix Makefiles +//Generator instance identifier. +CMAKE_GENERATOR_INSTANCE:INTERNAL= +//Name of generator platform. +CMAKE_GENERATOR_PLATFORM:INTERNAL= +//Name of generator toolset. +CMAKE_GENERATOR_TOOLSET:INTERNAL= +//Test CMAKE_HAVE_LIBC_PTHREAD +CMAKE_HAVE_LIBC_PTHREAD:INTERNAL=1 +//Have include pthread.h +CMAKE_HAVE_PTHREAD_H:INTERNAL=1 +//Source directory with the top level CMakeLists.txt file for this +// project +CMAKE_HOME_DIRECTORY:INTERNAL=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control +//Install .so files without execute permission. +CMAKE_INSTALL_SO_NO_EXE:INTERNAL=1 +//ADVANCED property for variable: CMAKE_LINKER +CMAKE_LINKER-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MAKE_PROGRAM +CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS +CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG +CMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL +CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE +CMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_NM +CMAKE_NM-ADVANCED:INTERNAL=1 +//number of local generators +CMAKE_NUMBER_OF_MAKEFILES:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJCOPY +CMAKE_OBJCOPY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_OBJDUMP +CMAKE_OBJDUMP-ADVANCED:INTERNAL=1 +//Platform information initialized +CMAKE_PLATFORM_INFO_INITIALIZED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_RANLIB +CMAKE_RANLIB-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_READELF +CMAKE_READELF-ADVANCED:INTERNAL=1 +//Path to CMake installation. +CMAKE_ROOT:INTERNAL=/usr/share/cmake-3.22 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS +CMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG +CMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL +CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE +CMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH +CMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_SKIP_RPATH +CMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS +CMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG +CMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL +CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE +CMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO +CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: CMAKE_STRIP +CMAKE_STRIP-ADVANCED:INTERNAL=1 +//uname command +CMAKE_UNAME:INTERNAL=/usr/bin/uname +//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE +CMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1 +//Details about finding FastRTPS +FIND_PACKAGE_MESSAGE_DETAILS_FastRTPS:INTERNAL=[/opt/ros/humble/include][/opt/ros/humble/lib/libfastrtps.so;/opt/ros/humble/lib/libfastcdr.so][v()] +//Details about finding OpenSSL +FIND_PACKAGE_MESSAGE_DETAILS_OpenSSL:INTERNAL=[/usr/lib/x86_64-linux-gnu/libcrypto.so][/usr/include][c ][v3.0.2()] +//Details about finding Python3 +FIND_PACKAGE_MESSAGE_DETAILS_Python3:INTERNAL=[/usr/bin/python3][cfound components: Interpreter ][v3.10.12()] +//Details about finding Threads +FIND_PACKAGE_MESSAGE_DETAILS_Threads:INTERNAL=[TRUE][v()] +//ADVANCED property for variable: OPENSSL_CRYPTO_LIBRARY +OPENSSL_CRYPTO_LIBRARY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OPENSSL_INCLUDE_DIR +OPENSSL_INCLUDE_DIR-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: OPENSSL_SSL_LIBRARY +OPENSSL_SSL_LIBRARY-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: PKG_CONFIG_ARGN +PKG_CONFIG_ARGN-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: PKG_CONFIG_EXECUTABLE +PKG_CONFIG_EXECUTABLE-ADVANCED:INTERNAL=1 +_OPENSSL_CFLAGS:INTERNAL= +_OPENSSL_CFLAGS_I:INTERNAL= +_OPENSSL_CFLAGS_OTHER:INTERNAL= +_OPENSSL_FOUND:INTERNAL=1 +_OPENSSL_INCLUDEDIR:INTERNAL=/usr/include +_OPENSSL_INCLUDE_DIRS:INTERNAL= +_OPENSSL_LDFLAGS:INTERNAL=-L/usr/lib/x86_64-linux-gnu;-lssl;-lcrypto +_OPENSSL_LDFLAGS_OTHER:INTERNAL= +_OPENSSL_LIBDIR:INTERNAL=/usr/lib/x86_64-linux-gnu +_OPENSSL_LIBRARIES:INTERNAL=ssl;crypto +_OPENSSL_LIBRARY_DIRS:INTERNAL=/usr/lib/x86_64-linux-gnu +_OPENSSL_LIBS:INTERNAL= +_OPENSSL_LIBS_L:INTERNAL= +_OPENSSL_LIBS_OTHER:INTERNAL= +_OPENSSL_LIBS_PATHS:INTERNAL= +_OPENSSL_MODULE_NAME:INTERNAL=openssl +_OPENSSL_PREFIX:INTERNAL=/usr +_OPENSSL_STATIC_CFLAGS:INTERNAL= +_OPENSSL_STATIC_CFLAGS_I:INTERNAL= +_OPENSSL_STATIC_CFLAGS_OTHER:INTERNAL= +_OPENSSL_STATIC_INCLUDE_DIRS:INTERNAL= +_OPENSSL_STATIC_LDFLAGS:INTERNAL=-L/usr/lib/x86_64-linux-gnu;-lssl;-lcrypto;-ldl;-pthread +_OPENSSL_STATIC_LDFLAGS_OTHER:INTERNAL=-pthread +_OPENSSL_STATIC_LIBDIR:INTERNAL= +_OPENSSL_STATIC_LIBRARIES:INTERNAL=ssl;crypto;dl +_OPENSSL_STATIC_LIBRARY_DIRS:INTERNAL=/usr/lib/x86_64-linux-gnu +_OPENSSL_STATIC_LIBS:INTERNAL= +_OPENSSL_STATIC_LIBS_L:INTERNAL= +_OPENSSL_STATIC_LIBS_OTHER:INTERNAL= +_OPENSSL_STATIC_LIBS_PATHS:INTERNAL= +_OPENSSL_VERSION:INTERNAL=3.0.2 +_OPENSSL_openssl_INCLUDEDIR:INTERNAL= +_OPENSSL_openssl_LIBDIR:INTERNAL= +_OPENSSL_openssl_PREFIX:INTERNAL= +_OPENSSL_openssl_VERSION:INTERNAL= +_Python3_EXECUTABLE:INTERNAL=/usr/bin/python3 +//Python3 Properties +_Python3_INTERPRETER_PROPERTIES:INTERNAL=Python;3;10;12;64;;cpython-310-x86_64-linux-gnu;/usr/lib/python3.10;/usr/lib/python3.10;/usr/lib/python3/dist-packages;/usr/lib/python3/dist-packages +_Python3_INTERPRETER_SIGNATURE:INTERNAL=0f3e53742e142b1d9e50e4ca5b901dd8 +__pkg_config_arguments__OPENSSL:INTERNAL=QUIET;openssl +__pkg_config_checked__OPENSSL:INTERNAL=1 +//ADVANCED property for variable: pkgcfg_lib__OPENSSL_crypto +pkgcfg_lib__OPENSSL_crypto-ADVANCED:INTERNAL=1 +//ADVANCED property for variable: pkgcfg_lib__OPENSSL_ssl +pkgcfg_lib__OPENSSL_ssl-ADVANCED:INTERNAL=1 +prefix_result:INTERNAL=/usr/lib/x86_64-linux-gnu + diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CMakeCCompiler.cmake b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeCCompiler.cmake new file mode 100644 index 0000000..f4819fd --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeCCompiler.cmake @@ -0,0 +1,72 @@ +set(CMAKE_C_COMPILER "/usr/bin/cc") +set(CMAKE_C_COMPILER_ARG1 "") +set(CMAKE_C_COMPILER_ID "GNU") +set(CMAKE_C_COMPILER_VERSION "11.4.0") +set(CMAKE_C_COMPILER_VERSION_INTERNAL "") +set(CMAKE_C_COMPILER_WRAPPER "") +set(CMAKE_C_STANDARD_COMPUTED_DEFAULT "17") +set(CMAKE_C_EXTENSIONS_COMPUTED_DEFAULT "ON") +set(CMAKE_C_COMPILE_FEATURES "c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert;c_std_17;c_std_23") +set(CMAKE_C90_COMPILE_FEATURES "c_std_90;c_function_prototypes") +set(CMAKE_C99_COMPILE_FEATURES "c_std_99;c_restrict;c_variadic_macros") +set(CMAKE_C11_COMPILE_FEATURES "c_std_11;c_static_assert") +set(CMAKE_C17_COMPILE_FEATURES "c_std_17") +set(CMAKE_C23_COMPILE_FEATURES "c_std_23") + +set(CMAKE_C_PLATFORM_ID "Linux") +set(CMAKE_C_SIMULATE_ID "") +set(CMAKE_C_COMPILER_FRONTEND_VARIANT "") +set(CMAKE_C_SIMULATE_VERSION "") + + + + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_C_COMPILER_AR "/usr/bin/gcc-ar-11") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_C_COMPILER_RANLIB "/usr/bin/gcc-ranlib-11") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_MT "") +set(CMAKE_COMPILER_IS_GNUCC 1) +set(CMAKE_C_COMPILER_LOADED 1) +set(CMAKE_C_COMPILER_WORKS TRUE) +set(CMAKE_C_ABI_COMPILED TRUE) + +set(CMAKE_C_COMPILER_ENV_VAR "CC") + +set(CMAKE_C_COMPILER_ID_RUN 1) +set(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m) +set(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC) +set(CMAKE_C_LINKER_PREFERENCE 10) + +# Save compiler ABI information. +set(CMAKE_C_SIZEOF_DATA_PTR "8") +set(CMAKE_C_COMPILER_ABI "ELF") +set(CMAKE_C_BYTE_ORDER "LITTLE_ENDIAN") +set(CMAKE_C_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_C_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_C_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_C_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_C_COMPILER_ABI}") +endif() + +if(CMAKE_C_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + +set(CMAKE_C_CL_SHOWINCLUDES_PREFIX "") +if(CMAKE_C_CL_SHOWINCLUDES_PREFIX) + set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_C_CL_SHOWINCLUDES_PREFIX}") +endif() + + + + + +set(CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES "/usr/local/etherlab/include;/usr/lib/gcc/x86_64-linux-gnu/11/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include") +set(CMAKE_C_IMPLICIT_LINK_LIBRARIES "gcc;gcc_s;c;gcc;gcc_s") +set(CMAKE_C_IMPLICIT_LINK_DIRECTORIES "/usr/local/etherlab/lib;/usr/lib/gcc/x86_64-linux-gnu/11;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CMakeCXXCompiler.cmake b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeCXXCompiler.cmake new file mode 100644 index 0000000..eafd135 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeCXXCompiler.cmake @@ -0,0 +1,83 @@ +set(CMAKE_CXX_COMPILER "/usr/bin/c++") +set(CMAKE_CXX_COMPILER_ARG1 "") +set(CMAKE_CXX_COMPILER_ID "GNU") +set(CMAKE_CXX_COMPILER_VERSION "11.4.0") +set(CMAKE_CXX_COMPILER_VERSION_INTERNAL "") +set(CMAKE_CXX_COMPILER_WRAPPER "") +set(CMAKE_CXX_STANDARD_COMPUTED_DEFAULT "17") +set(CMAKE_CXX_EXTENSIONS_COMPUTED_DEFAULT "ON") +set(CMAKE_CXX_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters;cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates;cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates;cxx_std_17;cxx_std_20;cxx_std_23") +set(CMAKE_CXX98_COMPILE_FEATURES "cxx_std_98;cxx_template_template_parameters") +set(CMAKE_CXX11_COMPILE_FEATURES "cxx_std_11;cxx_alias_templates;cxx_alignas;cxx_alignof;cxx_attributes;cxx_auto_type;cxx_constexpr;cxx_decltype;cxx_decltype_incomplete_return_types;cxx_default_function_template_args;cxx_defaulted_functions;cxx_defaulted_move_initializers;cxx_delegating_constructors;cxx_deleted_functions;cxx_enum_forward_declarations;cxx_explicit_conversions;cxx_extended_friend_declarations;cxx_extern_templates;cxx_final;cxx_func_identifier;cxx_generalized_initializers;cxx_inheriting_constructors;cxx_inline_namespaces;cxx_lambdas;cxx_local_type_template_args;cxx_long_long_type;cxx_noexcept;cxx_nonstatic_member_init;cxx_nullptr;cxx_override;cxx_range_for;cxx_raw_string_literals;cxx_reference_qualified_functions;cxx_right_angle_brackets;cxx_rvalue_references;cxx_sizeof_member;cxx_static_assert;cxx_strong_enums;cxx_thread_local;cxx_trailing_return_types;cxx_unicode_literals;cxx_uniform_initialization;cxx_unrestricted_unions;cxx_user_literals;cxx_variadic_macros;cxx_variadic_templates") +set(CMAKE_CXX14_COMPILE_FEATURES "cxx_std_14;cxx_aggregate_default_initializers;cxx_attribute_deprecated;cxx_binary_literals;cxx_contextual_conversions;cxx_decltype_auto;cxx_digit_separators;cxx_generic_lambdas;cxx_lambda_init_captures;cxx_relaxed_constexpr;cxx_return_type_deduction;cxx_variable_templates") +set(CMAKE_CXX17_COMPILE_FEATURES "cxx_std_17") +set(CMAKE_CXX20_COMPILE_FEATURES "cxx_std_20") +set(CMAKE_CXX23_COMPILE_FEATURES "cxx_std_23") + +set(CMAKE_CXX_PLATFORM_ID "Linux") +set(CMAKE_CXX_SIMULATE_ID "") +set(CMAKE_CXX_COMPILER_FRONTEND_VARIANT "") +set(CMAKE_CXX_SIMULATE_VERSION "") + + + + +set(CMAKE_AR "/usr/bin/ar") +set(CMAKE_CXX_COMPILER_AR "/usr/bin/gcc-ar-11") +set(CMAKE_RANLIB "/usr/bin/ranlib") +set(CMAKE_CXX_COMPILER_RANLIB "/usr/bin/gcc-ranlib-11") +set(CMAKE_LINKER "/usr/bin/ld") +set(CMAKE_MT "") +set(CMAKE_COMPILER_IS_GNUCXX 1) +set(CMAKE_CXX_COMPILER_LOADED 1) +set(CMAKE_CXX_COMPILER_WORKS TRUE) +set(CMAKE_CXX_ABI_COMPILED TRUE) + +set(CMAKE_CXX_COMPILER_ENV_VAR "CXX") + +set(CMAKE_CXX_COMPILER_ID_RUN 1) +set(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;m;mm;mpp;CPP;ixx;cppm) +set(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC) + +foreach (lang C OBJC OBJCXX) + if (CMAKE_${lang}_COMPILER_ID_RUN) + foreach(extension IN LISTS CMAKE_${lang}_SOURCE_FILE_EXTENSIONS) + list(REMOVE_ITEM CMAKE_CXX_SOURCE_FILE_EXTENSIONS ${extension}) + endforeach() + endif() +endforeach() + +set(CMAKE_CXX_LINKER_PREFERENCE 30) +set(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1) + +# Save compiler ABI information. +set(CMAKE_CXX_SIZEOF_DATA_PTR "8") +set(CMAKE_CXX_COMPILER_ABI "ELF") +set(CMAKE_CXX_BYTE_ORDER "LITTLE_ENDIAN") +set(CMAKE_CXX_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") + +if(CMAKE_CXX_SIZEOF_DATA_PTR) + set(CMAKE_SIZEOF_VOID_P "${CMAKE_CXX_SIZEOF_DATA_PTR}") +endif() + +if(CMAKE_CXX_COMPILER_ABI) + set(CMAKE_INTERNAL_PLATFORM_ABI "${CMAKE_CXX_COMPILER_ABI}") +endif() + +if(CMAKE_CXX_LIBRARY_ARCHITECTURE) + set(CMAKE_LIBRARY_ARCHITECTURE "x86_64-linux-gnu") +endif() + +set(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX "") +if(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX) + set(CMAKE_CL_SHOWINCLUDES_PREFIX "${CMAKE_CXX_CL_SHOWINCLUDES_PREFIX}") +endif() + + + + + +set(CMAKE_CXX_IMPLICIT_INCLUDE_DIRECTORIES "/usr/include/c++/11;/usr/include/x86_64-linux-gnu/c++/11;/usr/include/c++/11/backward;/usr/lib/gcc/x86_64-linux-gnu/11/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include") +set(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES "stdc++;m;gcc_s;gcc;c;gcc_s;gcc") +set(CMAKE_CXX_IMPLICIT_LINK_DIRECTORIES "/usr/local/etherlab/lib;/usr/lib/gcc/x86_64-linux-gnu/11;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib") +set(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES "") diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CMakeDetermineCompilerABI_C.bin b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeDetermineCompilerABI_C.bin new file mode 100755 index 0000000..06dd536 Binary files /dev/null and b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeDetermineCompilerABI_C.bin differ diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CMakeDetermineCompilerABI_CXX.bin b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeDetermineCompilerABI_CXX.bin new file mode 100755 index 0000000..8d4b8ab Binary files /dev/null and b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeDetermineCompilerABI_CXX.bin differ diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CMakeSystem.cmake b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeSystem.cmake new file mode 100644 index 0000000..4911504 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/3.22.1/CMakeSystem.cmake @@ -0,0 +1,15 @@ +set(CMAKE_HOST_SYSTEM "Linux-6.8.0-79-generic") +set(CMAKE_HOST_SYSTEM_NAME "Linux") +set(CMAKE_HOST_SYSTEM_VERSION "6.8.0-79-generic") +set(CMAKE_HOST_SYSTEM_PROCESSOR "x86_64") + + + +set(CMAKE_SYSTEM "Linux-6.8.0-79-generic") +set(CMAKE_SYSTEM_NAME "Linux") +set(CMAKE_SYSTEM_VERSION "6.8.0-79-generic") +set(CMAKE_SYSTEM_PROCESSOR "x86_64") + +set(CMAKE_CROSSCOMPILING "FALSE") + +set(CMAKE_SYSTEM_LOADED 1) diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdC/CMakeCCompilerId.c b/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdC/CMakeCCompilerId.c new file mode 100644 index 0000000..41b99d7 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdC/CMakeCCompilerId.c @@ -0,0 +1,803 @@ +#ifdef __cplusplus +# error "A C++ compiler has been selected for C." +#endif + +#if defined(__18CXX) +# define ID_VOID_MAIN +#endif +#if defined(__CLASSIC_C__) +/* cv-qualifiers did not exist in K&R C */ +# define const +# define volatile +#endif + +#if !defined(__has_include) +/* If the compiler does not have __has_include, pretend the answer is + always no. */ +# define __has_include(x) 0 +#endif + + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" +# if defined(_MSC_VER) +# define SIMULATE_ID "MSVC" +# endif +# if defined(__GNUC__) +# define SIMULATE_ID "GNU" +# endif + /* __INTEL_COMPILER = VRP prior to 2021, and then VVVV for 2021 and later, + except that a few beta releases use the old format with V=2021. */ +# if __INTEL_COMPILER < 2021 || __INTEL_COMPILER == 202110 || __INTEL_COMPILER == 202111 +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# if defined(__INTEL_COMPILER_UPDATE) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE) +# else +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# endif +# else +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER_UPDATE) + /* The third version component from --version is an update index, + but no macro is provided for it. */ +# define COMPILER_VERSION_PATCH DEC(0) +# endif +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif +# if defined(_MSC_VER) + /* _MSC_VER = VVRR */ +# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) +# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) +# endif +# if defined(__GNUC__) +# define SIMULATE_VERSION_MAJOR DEC(__GNUC__) +# elif defined(__GNUG__) +# define SIMULATE_VERSION_MAJOR DEC(__GNUG__) +# endif +# if defined(__GNUC_MINOR__) +# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__) +# endif +# if defined(__GNUC_PATCHLEVEL__) +# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif (defined(__clang__) && defined(__INTEL_CLANG_COMPILER)) || defined(__INTEL_LLVM_COMPILER) +# define COMPILER_ID "IntelLLVM" +#if defined(_MSC_VER) +# define SIMULATE_ID "MSVC" +#endif +#if defined(__GNUC__) +# define SIMULATE_ID "GNU" +#endif +/* __INTEL_LLVM_COMPILER = VVVVRP prior to 2021.2.0, VVVVRRPP for 2021.2.0 and + * later. Look for 6 digit vs. 8 digit version number to decide encoding. + * VVVV is no smaller than the current year when a version is released. + */ +#if __INTEL_LLVM_COMPILER < 1000000L +# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 10) +#else +# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/10000) +# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 100) +#endif +#if defined(_MSC_VER) + /* _MSC_VER = VVRR */ +# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) +# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) +#endif +#if defined(__GNUC__) +# define SIMULATE_VERSION_MAJOR DEC(__GNUC__) +#elif defined(__GNUG__) +# define SIMULATE_VERSION_MAJOR DEC(__GNUG__) +#endif +#if defined(__GNUC_MINOR__) +# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__) +#endif +#if defined(__GNUC_PATCHLEVEL__) +# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +#endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) && __WATCOMC__ < 1200 +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) +# if (__WATCOMC__ % 10) > 0 +# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) +# endif + +#elif defined(__WATCOMC__) +# define COMPILER_ID "OpenWatcom" + /* __WATCOMC__ = VVRP + 1100 */ +# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100) +# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) +# if (__WATCOMC__ % 10) > 0 +# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) +# endif + +#elif defined(__SUNPRO_C) +# define COMPILER_ID "SunPro" +# if __SUNPRO_C >= 0x5100 + /* __SUNPRO_C = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# else + /* __SUNPRO_CC = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_C & 0xF) +# endif + +#elif defined(__HP_cc) +# define COMPILER_ID "HP" + /* __HP_cc = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_cc % 100) + +#elif defined(__DECC) +# define COMPILER_ID "Compaq" + /* __DECC_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECC_VER % 10000) + +#elif defined(__IBMC__) && defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) + +#elif defined(__ibmxl__) && defined(__clang__) +# define COMPILER_ID "XLClang" +# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__) +# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__) +# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__) +# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__) + + +#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ >= 800 +# define COMPILER_ID "XL" + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) + +#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ < 800 +# define COMPILER_ID "VisualAge" + /* __IBMC__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMC__ % 10) + +#elif defined(__NVCOMPILER) +# define COMPILER_ID "NVHPC" +# define COMPILER_VERSION_MAJOR DEC(__NVCOMPILER_MAJOR__) +# define COMPILER_VERSION_MINOR DEC(__NVCOMPILER_MINOR__) +# if defined(__NVCOMPILER_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__NVCOMPILER_PATCHLEVEL__) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__CLANG_FUJITSU) +# define COMPILER_ID "FujitsuClang" +# define COMPILER_VERSION_MAJOR DEC(__FCC_major__) +# define COMPILER_VERSION_MINOR DEC(__FCC_minor__) +# define COMPILER_VERSION_PATCH DEC(__FCC_patchlevel__) +# define COMPILER_VERSION_INTERNAL_STR __clang_version__ + + +#elif defined(__FUJITSU) +# define COMPILER_ID "Fujitsu" +# if defined(__FCC_version__) +# define COMPILER_VERSION __FCC_version__ +# elif defined(__FCC_major__) +# define COMPILER_VERSION_MAJOR DEC(__FCC_major__) +# define COMPILER_VERSION_MINOR DEC(__FCC_minor__) +# define COMPILER_VERSION_PATCH DEC(__FCC_patchlevel__) +# endif +# if defined(__fcc_version) +# define COMPILER_VERSION_INTERNAL DEC(__fcc_version) +# elif defined(__FCC_VERSION) +# define COMPILER_VERSION_INTERNAL DEC(__FCC_VERSION) +# endif + + +#elif defined(__ghs__) +# define COMPILER_ID "GHS" +/* __GHS_VERSION_NUMBER = VVVVRP */ +# ifdef __GHS_VERSION_NUMBER +# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100) +# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10) +# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER % 10) +# endif + +#elif defined(__TINYC__) +# define COMPILER_ID "TinyCC" + +#elif defined(__BCC__) +# define COMPILER_ID "Bruce" + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__ARMCC_VERSION) && !defined(__clang__) +# define COMPILER_ID "ARMCC" +#if __ARMCC_VERSION >= 1000000 + /* __ARMCC_VERSION = VRRPPPP */ + # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000) + # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100) + # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) +#else + /* __ARMCC_VERSION = VRPPPP */ + # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000) + # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10) + # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) +#endif + + +#elif defined(__clang__) && defined(__apple_build_version__) +# define COMPILER_ID "AppleClang" +# if defined(_MSC_VER) +# define SIMULATE_ID "MSVC" +# endif +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) +# if defined(_MSC_VER) + /* _MSC_VER = VVRR */ +# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) +# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) +# endif +# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__) + +#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION) +# define COMPILER_ID "ARMClang" + # define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000) + # define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100) + # define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION % 10000) +# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION) + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# if defined(_MSC_VER) +# define SIMULATE_ID "MSVC" +# endif +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) +# if defined(_MSC_VER) + /* _MSC_VER = VVRR */ +# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) +# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) +# endif + +#elif defined(__GNUC__) +# define COMPILER_ID "GNU" +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# if defined(__GNUC_MINOR__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# endif +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" +#if defined(__VISUALDSPVERSION__) + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) +#endif + +#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" +# if defined(__VER__) && defined(__ICCARM__) +# define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000) +# define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000) +# define COMPILER_VERSION_PATCH DEC((__VER__) % 1000) +# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__) +# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__) || defined(__ICCSTM8__)) +# define COMPILER_VERSION_MAJOR DEC((__VER__) / 100) +# define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100)) +# define COMPILER_VERSION_PATCH DEC(__SUBVERSION__) +# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__) +# endif + +#elif defined(__SDCC_VERSION_MAJOR) || defined(SDCC) +# define COMPILER_ID "SDCC" +# if defined(__SDCC_VERSION_MAJOR) +# define COMPILER_VERSION_MAJOR DEC(__SDCC_VERSION_MAJOR) +# define COMPILER_VERSION_MINOR DEC(__SDCC_VERSION_MINOR) +# define COMPILER_VERSION_PATCH DEC(__SDCC_VERSION_PATCH) +# else + /* SDCC = VRP */ +# define COMPILER_VERSION_MAJOR DEC(SDCC/100) +# define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10) +# define COMPILER_VERSION_PATCH DEC(SDCC % 10) +# endif + + +/* These compilers are either not known or too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; +#ifdef SIMULATE_ID +char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]"; +#endif + +#ifdef __QNXNTO__ +char const* qnxnto = "INFO" ":" "qnxnto[]"; +#endif + +#if defined(__CRAYXT_COMPUTE_LINUX_TARGET) +char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]"; +#endif + +#define STRINGIFY_HELPER(X) #X +#define STRINGIFY(X) STRINGIFY_HELPER(X) + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__MSYS__) +# define PLATFORM_ID "MSYS" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#elif defined(__WATCOMC__) +# if defined(__LINUX__) +# define PLATFORM_ID "Linux" + +# elif defined(__DOS__) +# define PLATFORM_ID "DOS" + +# elif defined(__OS2__) +# define PLATFORM_ID "OS2" + +# elif defined(__WINDOWS__) +# define PLATFORM_ID "Windows3x" + +# elif defined(__VXWORKS__) +# define PLATFORM_ID "VxWorks" + +# else /* unknown platform */ +# define PLATFORM_ID +# endif + +#elif defined(__INTEGRITY) +# if defined(INT_178B) +# define PLATFORM_ID "Integrity178" + +# else /* regular Integrity */ +# define PLATFORM_ID "Integrity" +# endif + +#else /* unknown platform */ +# define PLATFORM_ID + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_ARM64EC) +# define ARCHITECTURE_ID "ARM64EC" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM64) +# define ARCHITECTURE_ID "ARM64" + +# elif defined(_M_ARM) +# if _M_ARM == 4 +# define ARCHITECTURE_ID "ARMV4I" +# elif _M_ARM == 5 +# define ARCHITECTURE_ID "ARMV5I" +# else +# define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM) +# endif + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#elif defined(__WATCOMC__) +# if defined(_M_I86) +# define ARCHITECTURE_ID "I86" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC) +# if defined(__ICCARM__) +# define ARCHITECTURE_ID "ARM" + +# elif defined(__ICCRX__) +# define ARCHITECTURE_ID "RX" + +# elif defined(__ICCRH850__) +# define ARCHITECTURE_ID "RH850" + +# elif defined(__ICCRL78__) +# define ARCHITECTURE_ID "RL78" + +# elif defined(__ICCRISCV__) +# define ARCHITECTURE_ID "RISCV" + +# elif defined(__ICCAVR__) +# define ARCHITECTURE_ID "AVR" + +# elif defined(__ICC430__) +# define ARCHITECTURE_ID "MSP430" + +# elif defined(__ICCV850__) +# define ARCHITECTURE_ID "V850" + +# elif defined(__ICC8051__) +# define ARCHITECTURE_ID "8051" + +# elif defined(__ICCSTM8__) +# define ARCHITECTURE_ID "STM8" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#elif defined(__ghs__) +# if defined(__PPC64__) +# define ARCHITECTURE_ID "PPC64" + +# elif defined(__ppc__) +# define ARCHITECTURE_ID "PPC" + +# elif defined(__ARM__) +# define ARCHITECTURE_ID "ARM" + +# elif defined(__x86_64__) +# define ARCHITECTURE_ID "x64" + +# elif defined(__i386__) +# define ARCHITECTURE_ID "X86" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#elif defined(__TI_COMPILER_VERSION__) +# if defined(__TI_ARM__) +# define ARCHITECTURE_ID "ARM" + +# elif defined(__MSP430__) +# define ARCHITECTURE_ID "MSP430" + +# elif defined(__TMS320C28XX__) +# define ARCHITECTURE_ID "TMS320C28x" + +# elif defined(__TMS320C6X__) || defined(_TMS320C6X) +# define ARCHITECTURE_ID "TMS320C6x" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number. */ +#ifdef COMPILER_VERSION +char const* info_version = "INFO" ":" "compiler_version[" COMPILER_VERSION "]"; + +/* Construct a string literal encoding the version number components. */ +#elif defined(COMPILER_VERSION_MAJOR) +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct a string literal encoding the internal version number. */ +#ifdef COMPILER_VERSION_INTERNAL +char const info_version_internal[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_', + 'i','n','t','e','r','n','a','l','[', + COMPILER_VERSION_INTERNAL,']','\0'}; +#elif defined(COMPILER_VERSION_INTERNAL_STR) +char const* info_version_internal = "INFO" ":" "compiler_version_internal[" COMPILER_VERSION_INTERNAL_STR "]"; +#endif + +/* Construct a string literal encoding the version number components. */ +#ifdef SIMULATE_VERSION_MAJOR +char const info_simulate_version[] = { + 'I', 'N', 'F', 'O', ':', + 's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[', + SIMULATE_VERSION_MAJOR, +# ifdef SIMULATE_VERSION_MINOR + '.', SIMULATE_VERSION_MINOR, +# ifdef SIMULATE_VERSION_PATCH + '.', SIMULATE_VERSION_PATCH, +# ifdef SIMULATE_VERSION_TWEAK + '.', SIMULATE_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +#if !defined(__STDC__) && !defined(__clang__) +# if defined(_MSC_VER) || defined(__ibmxl__) || defined(__IBMC__) +# define C_VERSION "90" +# else +# define C_VERSION +# endif +#elif __STDC_VERSION__ > 201710L +# define C_VERSION "23" +#elif __STDC_VERSION__ >= 201710L +# define C_VERSION "17" +#elif __STDC_VERSION__ >= 201000L +# define C_VERSION "11" +#elif __STDC_VERSION__ >= 199901L +# define C_VERSION "99" +#else +# define C_VERSION "90" +#endif +const char* info_language_standard_default = + "INFO" ":" "standard_default[" C_VERSION "]"; + +const char* info_language_extensions_default = "INFO" ":" "extensions_default[" +/* !defined(_MSC_VER) to exclude Clang's MSVC compatibility mode. */ +#if (defined(__clang__) || defined(__GNUC__) || \ + defined(__TI_COMPILER_VERSION__)) && \ + !defined(__STRICT_ANSI__) && !defined(_MSC_VER) + "ON" +#else + "OFF" +#endif +"]"; + +/*--------------------------------------------------------------------------*/ + +#ifdef ID_VOID_MAIN +void main() {} +#else +# if defined(__CLASSIC_C__) +int main(argc, argv) int argc; char *argv[]; +# else +int main(int argc, char* argv[]) +# endif +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; + require += info_arch[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif +#ifdef COMPILER_VERSION_INTERNAL + require += info_version_internal[argc]; +#endif +#ifdef SIMULATE_ID + require += info_simulate[argc]; +#endif +#ifdef SIMULATE_VERSION_MAJOR + require += info_simulate_version[argc]; +#endif +#if defined(__CRAYXT_COMPUTE_LINUX_TARGET) + require += info_cray[argc]; +#endif + require += info_language_standard_default[argc]; + require += info_language_extensions_default[argc]; + (void)argv; + return require; +} +#endif diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdC/a.out b/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdC/a.out new file mode 100755 index 0000000..8b8c27e Binary files /dev/null and b/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdC/a.out differ diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdCXX/CMakeCXXCompilerId.cpp b/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdCXX/CMakeCXXCompilerId.cpp new file mode 100644 index 0000000..25c62a8 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdCXX/CMakeCXXCompilerId.cpp @@ -0,0 +1,791 @@ +/* This source file must have a .cpp extension so that all C++ compilers + recognize the extension without flags. Borland does not know .cxx for + example. */ +#ifndef __cplusplus +# error "A C compiler has been selected for C++." +#endif + +#if !defined(__has_include) +/* If the compiler does not have __has_include, pretend the answer is + always no. */ +# define __has_include(x) 0 +#endif + + +/* Version number components: V=Version, R=Revision, P=Patch + Version date components: YYYY=Year, MM=Month, DD=Day */ + +#if defined(__COMO__) +# define COMPILER_ID "Comeau" + /* __COMO_VERSION__ = VRR */ +# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100) +# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100) + +#elif defined(__INTEL_COMPILER) || defined(__ICC) +# define COMPILER_ID "Intel" +# if defined(_MSC_VER) +# define SIMULATE_ID "MSVC" +# endif +# if defined(__GNUC__) +# define SIMULATE_ID "GNU" +# endif + /* __INTEL_COMPILER = VRP prior to 2021, and then VVVV for 2021 and later, + except that a few beta releases use the old format with V=2021. */ +# if __INTEL_COMPILER < 2021 || __INTEL_COMPILER == 202110 || __INTEL_COMPILER == 202111 +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10) +# if defined(__INTEL_COMPILER_UPDATE) +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE) +# else +# define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER % 10) +# endif +# else +# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER) +# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER_UPDATE) + /* The third version component from --version is an update index, + but no macro is provided for it. */ +# define COMPILER_VERSION_PATCH DEC(0) +# endif +# if defined(__INTEL_COMPILER_BUILD_DATE) + /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */ +# define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE) +# endif +# if defined(_MSC_VER) + /* _MSC_VER = VVRR */ +# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) +# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) +# endif +# if defined(__GNUC__) +# define SIMULATE_VERSION_MAJOR DEC(__GNUC__) +# elif defined(__GNUG__) +# define SIMULATE_VERSION_MAJOR DEC(__GNUG__) +# endif +# if defined(__GNUC_MINOR__) +# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__) +# endif +# if defined(__GNUC_PATCHLEVEL__) +# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif (defined(__clang__) && defined(__INTEL_CLANG_COMPILER)) || defined(__INTEL_LLVM_COMPILER) +# define COMPILER_ID "IntelLLVM" +#if defined(_MSC_VER) +# define SIMULATE_ID "MSVC" +#endif +#if defined(__GNUC__) +# define SIMULATE_ID "GNU" +#endif +/* __INTEL_LLVM_COMPILER = VVVVRP prior to 2021.2.0, VVVVRRPP for 2021.2.0 and + * later. Look for 6 digit vs. 8 digit version number to decide encoding. + * VVVV is no smaller than the current year when a version is released. + */ +#if __INTEL_LLVM_COMPILER < 1000000L +# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/100) +# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 10) +#else +# define COMPILER_VERSION_MAJOR DEC(__INTEL_LLVM_COMPILER/10000) +# define COMPILER_VERSION_MINOR DEC(__INTEL_LLVM_COMPILER/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__INTEL_LLVM_COMPILER % 100) +#endif +#if defined(_MSC_VER) + /* _MSC_VER = VVRR */ +# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) +# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) +#endif +#if defined(__GNUC__) +# define SIMULATE_VERSION_MAJOR DEC(__GNUC__) +#elif defined(__GNUG__) +# define SIMULATE_VERSION_MAJOR DEC(__GNUG__) +#endif +#if defined(__GNUC_MINOR__) +# define SIMULATE_VERSION_MINOR DEC(__GNUC_MINOR__) +#endif +#if defined(__GNUC_PATCHLEVEL__) +# define SIMULATE_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +#endif + +#elif defined(__PATHCC__) +# define COMPILER_ID "PathScale" +# define COMPILER_VERSION_MAJOR DEC(__PATHCC__) +# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__) +# if defined(__PATHCC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__) +# endif + +#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__) +# define COMPILER_ID "Embarcadero" +# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF) +# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF) +# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__ & 0xFFFF) + +#elif defined(__BORLANDC__) +# define COMPILER_ID "Borland" + /* __BORLANDC__ = 0xVRR */ +# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8) +# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF) + +#elif defined(__WATCOMC__) && __WATCOMC__ < 1200 +# define COMPILER_ID "Watcom" + /* __WATCOMC__ = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100) +# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) +# if (__WATCOMC__ % 10) > 0 +# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) +# endif + +#elif defined(__WATCOMC__) +# define COMPILER_ID "OpenWatcom" + /* __WATCOMC__ = VVRP + 1100 */ +# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100) +# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10) +# if (__WATCOMC__ % 10) > 0 +# define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10) +# endif + +#elif defined(__SUNPRO_CC) +# define COMPILER_ID "SunPro" +# if __SUNPRO_CC >= 0x5100 + /* __SUNPRO_CC = 0xVRRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# else + /* __SUNPRO_CC = 0xVRP */ +# define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8) +# define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF) +# define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC & 0xF) +# endif + +#elif defined(__HP_aCC) +# define COMPILER_ID "HP" + /* __HP_aCC = VVRRPP */ +# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000) +# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100) +# define COMPILER_VERSION_PATCH DEC(__HP_aCC % 100) + +#elif defined(__DECCXX) +# define COMPILER_ID "Compaq" + /* __DECCXX_VER = VVRRTPPPP */ +# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000) +# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000 % 100) +# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER % 10000) + +#elif defined(__IBMCPP__) && defined(__COMPILER_VER__) +# define COMPILER_ID "zOS" + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) + +#elif defined(__ibmxl__) && defined(__clang__) +# define COMPILER_ID "XLClang" +# define COMPILER_VERSION_MAJOR DEC(__ibmxl_version__) +# define COMPILER_VERSION_MINOR DEC(__ibmxl_release__) +# define COMPILER_VERSION_PATCH DEC(__ibmxl_modification__) +# define COMPILER_VERSION_TWEAK DEC(__ibmxl_ptf_fix_level__) + + +#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ >= 800 +# define COMPILER_ID "XL" + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) + +#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ < 800 +# define COMPILER_ID "VisualAge" + /* __IBMCPP__ = VRP */ +# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100) +# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10) +# define COMPILER_VERSION_PATCH DEC(__IBMCPP__ % 10) + +#elif defined(__NVCOMPILER) +# define COMPILER_ID "NVHPC" +# define COMPILER_VERSION_MAJOR DEC(__NVCOMPILER_MAJOR__) +# define COMPILER_VERSION_MINOR DEC(__NVCOMPILER_MINOR__) +# if defined(__NVCOMPILER_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__NVCOMPILER_PATCHLEVEL__) +# endif + +#elif defined(__PGI) +# define COMPILER_ID "PGI" +# define COMPILER_VERSION_MAJOR DEC(__PGIC__) +# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__) +# if defined(__PGIC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__) +# endif + +#elif defined(_CRAYC) +# define COMPILER_ID "Cray" +# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR) +# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR) + +#elif defined(__TI_COMPILER_VERSION__) +# define COMPILER_ID "TI" + /* __TI_COMPILER_VERSION__ = VVVRRRPPP */ +# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000) +# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000 % 1000) +# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__ % 1000) + +#elif defined(__CLANG_FUJITSU) +# define COMPILER_ID "FujitsuClang" +# define COMPILER_VERSION_MAJOR DEC(__FCC_major__) +# define COMPILER_VERSION_MINOR DEC(__FCC_minor__) +# define COMPILER_VERSION_PATCH DEC(__FCC_patchlevel__) +# define COMPILER_VERSION_INTERNAL_STR __clang_version__ + + +#elif defined(__FUJITSU) +# define COMPILER_ID "Fujitsu" +# if defined(__FCC_version__) +# define COMPILER_VERSION __FCC_version__ +# elif defined(__FCC_major__) +# define COMPILER_VERSION_MAJOR DEC(__FCC_major__) +# define COMPILER_VERSION_MINOR DEC(__FCC_minor__) +# define COMPILER_VERSION_PATCH DEC(__FCC_patchlevel__) +# endif +# if defined(__fcc_version) +# define COMPILER_VERSION_INTERNAL DEC(__fcc_version) +# elif defined(__FCC_VERSION) +# define COMPILER_VERSION_INTERNAL DEC(__FCC_VERSION) +# endif + + +#elif defined(__ghs__) +# define COMPILER_ID "GHS" +/* __GHS_VERSION_NUMBER = VVVVRP */ +# ifdef __GHS_VERSION_NUMBER +# define COMPILER_VERSION_MAJOR DEC(__GHS_VERSION_NUMBER / 100) +# define COMPILER_VERSION_MINOR DEC(__GHS_VERSION_NUMBER / 10 % 10) +# define COMPILER_VERSION_PATCH DEC(__GHS_VERSION_NUMBER % 10) +# endif + +#elif defined(__SCO_VERSION__) +# define COMPILER_ID "SCO" + +#elif defined(__ARMCC_VERSION) && !defined(__clang__) +# define COMPILER_ID "ARMCC" +#if __ARMCC_VERSION >= 1000000 + /* __ARMCC_VERSION = VRRPPPP */ + # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000) + # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100) + # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) +#else + /* __ARMCC_VERSION = VRPPPP */ + # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000) + # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10) + # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION % 10000) +#endif + + +#elif defined(__clang__) && defined(__apple_build_version__) +# define COMPILER_ID "AppleClang" +# if defined(_MSC_VER) +# define SIMULATE_ID "MSVC" +# endif +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) +# if defined(_MSC_VER) + /* _MSC_VER = VVRR */ +# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) +# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) +# endif +# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__) + +#elif defined(__clang__) && defined(__ARMCOMPILER_VERSION) +# define COMPILER_ID "ARMClang" + # define COMPILER_VERSION_MAJOR DEC(__ARMCOMPILER_VERSION/1000000) + # define COMPILER_VERSION_MINOR DEC(__ARMCOMPILER_VERSION/10000 % 100) + # define COMPILER_VERSION_PATCH DEC(__ARMCOMPILER_VERSION % 10000) +# define COMPILER_VERSION_INTERNAL DEC(__ARMCOMPILER_VERSION) + +#elif defined(__clang__) +# define COMPILER_ID "Clang" +# if defined(_MSC_VER) +# define SIMULATE_ID "MSVC" +# endif +# define COMPILER_VERSION_MAJOR DEC(__clang_major__) +# define COMPILER_VERSION_MINOR DEC(__clang_minor__) +# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__) +# if defined(_MSC_VER) + /* _MSC_VER = VVRR */ +# define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100) +# define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100) +# endif + +#elif defined(__GNUC__) || defined(__GNUG__) +# define COMPILER_ID "GNU" +# if defined(__GNUC__) +# define COMPILER_VERSION_MAJOR DEC(__GNUC__) +# else +# define COMPILER_VERSION_MAJOR DEC(__GNUG__) +# endif +# if defined(__GNUC_MINOR__) +# define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__) +# endif +# if defined(__GNUC_PATCHLEVEL__) +# define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__) +# endif + +#elif defined(_MSC_VER) +# define COMPILER_ID "MSVC" + /* _MSC_VER = VVRR */ +# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100) +# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100) +# if defined(_MSC_FULL_VER) +# if _MSC_VER >= 1400 + /* _MSC_FULL_VER = VVRRPPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000) +# else + /* _MSC_FULL_VER = VVRRPPPP */ +# define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000) +# endif +# endif +# if defined(_MSC_BUILD) +# define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD) +# endif + +#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__) +# define COMPILER_ID "ADSP" +#if defined(__VISUALDSPVERSION__) + /* __VISUALDSPVERSION__ = 0xVVRRPP00 */ +# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24) +# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF) +# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8 & 0xFF) +#endif + +#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC) +# define COMPILER_ID "IAR" +# if defined(__VER__) && defined(__ICCARM__) +# define COMPILER_VERSION_MAJOR DEC((__VER__) / 1000000) +# define COMPILER_VERSION_MINOR DEC(((__VER__) / 1000) % 1000) +# define COMPILER_VERSION_PATCH DEC((__VER__) % 1000) +# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__) +# elif defined(__VER__) && (defined(__ICCAVR__) || defined(__ICCRX__) || defined(__ICCRH850__) || defined(__ICCRL78__) || defined(__ICC430__) || defined(__ICCRISCV__) || defined(__ICCV850__) || defined(__ICC8051__) || defined(__ICCSTM8__)) +# define COMPILER_VERSION_MAJOR DEC((__VER__) / 100) +# define COMPILER_VERSION_MINOR DEC((__VER__) - (((__VER__) / 100)*100)) +# define COMPILER_VERSION_PATCH DEC(__SUBVERSION__) +# define COMPILER_VERSION_INTERNAL DEC(__IAR_SYSTEMS_ICC__) +# endif + + +/* These compilers are either not known or too old to define an + identification macro. Try to identify the platform and guess that + it is the native compiler. */ +#elif defined(__hpux) || defined(__hpua) +# define COMPILER_ID "HP" + +#else /* unknown compiler */ +# define COMPILER_ID "" +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_compiler = "INFO" ":" "compiler[" COMPILER_ID "]"; +#ifdef SIMULATE_ID +char const* info_simulate = "INFO" ":" "simulate[" SIMULATE_ID "]"; +#endif + +#ifdef __QNXNTO__ +char const* qnxnto = "INFO" ":" "qnxnto[]"; +#endif + +#if defined(__CRAYXT_COMPUTE_LINUX_TARGET) +char const *info_cray = "INFO" ":" "compiler_wrapper[CrayPrgEnv]"; +#endif + +#define STRINGIFY_HELPER(X) #X +#define STRINGIFY(X) STRINGIFY_HELPER(X) + +/* Identify known platforms by name. */ +#if defined(__linux) || defined(__linux__) || defined(linux) +# define PLATFORM_ID "Linux" + +#elif defined(__MSYS__) +# define PLATFORM_ID "MSYS" + +#elif defined(__CYGWIN__) +# define PLATFORM_ID "Cygwin" + +#elif defined(__MINGW32__) +# define PLATFORM_ID "MinGW" + +#elif defined(__APPLE__) +# define PLATFORM_ID "Darwin" + +#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32) +# define PLATFORM_ID "Windows" + +#elif defined(__FreeBSD__) || defined(__FreeBSD) +# define PLATFORM_ID "FreeBSD" + +#elif defined(__NetBSD__) || defined(__NetBSD) +# define PLATFORM_ID "NetBSD" + +#elif defined(__OpenBSD__) || defined(__OPENBSD) +# define PLATFORM_ID "OpenBSD" + +#elif defined(__sun) || defined(sun) +# define PLATFORM_ID "SunOS" + +#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__) +# define PLATFORM_ID "AIX" + +#elif defined(__hpux) || defined(__hpux__) +# define PLATFORM_ID "HP-UX" + +#elif defined(__HAIKU__) +# define PLATFORM_ID "Haiku" + +#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS) +# define PLATFORM_ID "BeOS" + +#elif defined(__QNX__) || defined(__QNXNTO__) +# define PLATFORM_ID "QNX" + +#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__) +# define PLATFORM_ID "Tru64" + +#elif defined(__riscos) || defined(__riscos__) +# define PLATFORM_ID "RISCos" + +#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__) +# define PLATFORM_ID "SINIX" + +#elif defined(__UNIX_SV__) +# define PLATFORM_ID "UNIX_SV" + +#elif defined(__bsdos__) +# define PLATFORM_ID "BSDOS" + +#elif defined(_MPRAS) || defined(MPRAS) +# define PLATFORM_ID "MP-RAS" + +#elif defined(__osf) || defined(__osf__) +# define PLATFORM_ID "OSF1" + +#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv) +# define PLATFORM_ID "SCO_SV" + +#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX) +# define PLATFORM_ID "ULTRIX" + +#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX) +# define PLATFORM_ID "Xenix" + +#elif defined(__WATCOMC__) +# if defined(__LINUX__) +# define PLATFORM_ID "Linux" + +# elif defined(__DOS__) +# define PLATFORM_ID "DOS" + +# elif defined(__OS2__) +# define PLATFORM_ID "OS2" + +# elif defined(__WINDOWS__) +# define PLATFORM_ID "Windows3x" + +# elif defined(__VXWORKS__) +# define PLATFORM_ID "VxWorks" + +# else /* unknown platform */ +# define PLATFORM_ID +# endif + +#elif defined(__INTEGRITY) +# if defined(INT_178B) +# define PLATFORM_ID "Integrity178" + +# else /* regular Integrity */ +# define PLATFORM_ID "Integrity" +# endif + +#else /* unknown platform */ +# define PLATFORM_ID + +#endif + +/* For windows compilers MSVC and Intel we can determine + the architecture of the compiler being used. This is because + the compilers do not have flags that can change the architecture, + but rather depend on which compiler is being used +*/ +#if defined(_WIN32) && defined(_MSC_VER) +# if defined(_M_IA64) +# define ARCHITECTURE_ID "IA64" + +# elif defined(_M_ARM64EC) +# define ARCHITECTURE_ID "ARM64EC" + +# elif defined(_M_X64) || defined(_M_AMD64) +# define ARCHITECTURE_ID "x64" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# elif defined(_M_ARM64) +# define ARCHITECTURE_ID "ARM64" + +# elif defined(_M_ARM) +# if _M_ARM == 4 +# define ARCHITECTURE_ID "ARMV4I" +# elif _M_ARM == 5 +# define ARCHITECTURE_ID "ARMV5I" +# else +# define ARCHITECTURE_ID "ARMV" STRINGIFY(_M_ARM) +# endif + +# elif defined(_M_MIPS) +# define ARCHITECTURE_ID "MIPS" + +# elif defined(_M_SH) +# define ARCHITECTURE_ID "SHx" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#elif defined(__WATCOMC__) +# if defined(_M_I86) +# define ARCHITECTURE_ID "I86" + +# elif defined(_M_IX86) +# define ARCHITECTURE_ID "X86" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#elif defined(__IAR_SYSTEMS_ICC__) || defined(__IAR_SYSTEMS_ICC) +# if defined(__ICCARM__) +# define ARCHITECTURE_ID "ARM" + +# elif defined(__ICCRX__) +# define ARCHITECTURE_ID "RX" + +# elif defined(__ICCRH850__) +# define ARCHITECTURE_ID "RH850" + +# elif defined(__ICCRL78__) +# define ARCHITECTURE_ID "RL78" + +# elif defined(__ICCRISCV__) +# define ARCHITECTURE_ID "RISCV" + +# elif defined(__ICCAVR__) +# define ARCHITECTURE_ID "AVR" + +# elif defined(__ICC430__) +# define ARCHITECTURE_ID "MSP430" + +# elif defined(__ICCV850__) +# define ARCHITECTURE_ID "V850" + +# elif defined(__ICC8051__) +# define ARCHITECTURE_ID "8051" + +# elif defined(__ICCSTM8__) +# define ARCHITECTURE_ID "STM8" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#elif defined(__ghs__) +# if defined(__PPC64__) +# define ARCHITECTURE_ID "PPC64" + +# elif defined(__ppc__) +# define ARCHITECTURE_ID "PPC" + +# elif defined(__ARM__) +# define ARCHITECTURE_ID "ARM" + +# elif defined(__x86_64__) +# define ARCHITECTURE_ID "x64" + +# elif defined(__i386__) +# define ARCHITECTURE_ID "X86" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#elif defined(__TI_COMPILER_VERSION__) +# if defined(__TI_ARM__) +# define ARCHITECTURE_ID "ARM" + +# elif defined(__MSP430__) +# define ARCHITECTURE_ID "MSP430" + +# elif defined(__TMS320C28XX__) +# define ARCHITECTURE_ID "TMS320C28x" + +# elif defined(__TMS320C6X__) || defined(_TMS320C6X) +# define ARCHITECTURE_ID "TMS320C6x" + +# else /* unknown architecture */ +# define ARCHITECTURE_ID "" +# endif + +#else +# define ARCHITECTURE_ID +#endif + +/* Convert integer to decimal digit literals. */ +#define DEC(n) \ + ('0' + (((n) / 10000000)%10)), \ + ('0' + (((n) / 1000000)%10)), \ + ('0' + (((n) / 100000)%10)), \ + ('0' + (((n) / 10000)%10)), \ + ('0' + (((n) / 1000)%10)), \ + ('0' + (((n) / 100)%10)), \ + ('0' + (((n) / 10)%10)), \ + ('0' + ((n) % 10)) + +/* Convert integer to hex digit literals. */ +#define HEX(n) \ + ('0' + ((n)>>28 & 0xF)), \ + ('0' + ((n)>>24 & 0xF)), \ + ('0' + ((n)>>20 & 0xF)), \ + ('0' + ((n)>>16 & 0xF)), \ + ('0' + ((n)>>12 & 0xF)), \ + ('0' + ((n)>>8 & 0xF)), \ + ('0' + ((n)>>4 & 0xF)), \ + ('0' + ((n) & 0xF)) + +/* Construct a string literal encoding the version number. */ +#ifdef COMPILER_VERSION +char const* info_version = "INFO" ":" "compiler_version[" COMPILER_VERSION "]"; + +/* Construct a string literal encoding the version number components. */ +#elif defined(COMPILER_VERSION_MAJOR) +char const info_version[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[', + COMPILER_VERSION_MAJOR, +# ifdef COMPILER_VERSION_MINOR + '.', COMPILER_VERSION_MINOR, +# ifdef COMPILER_VERSION_PATCH + '.', COMPILER_VERSION_PATCH, +# ifdef COMPILER_VERSION_TWEAK + '.', COMPILER_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct a string literal encoding the internal version number. */ +#ifdef COMPILER_VERSION_INTERNAL +char const info_version_internal[] = { + 'I', 'N', 'F', 'O', ':', + 'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','_', + 'i','n','t','e','r','n','a','l','[', + COMPILER_VERSION_INTERNAL,']','\0'}; +#elif defined(COMPILER_VERSION_INTERNAL_STR) +char const* info_version_internal = "INFO" ":" "compiler_version_internal[" COMPILER_VERSION_INTERNAL_STR "]"; +#endif + +/* Construct a string literal encoding the version number components. */ +#ifdef SIMULATE_VERSION_MAJOR +char const info_simulate_version[] = { + 'I', 'N', 'F', 'O', ':', + 's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[', + SIMULATE_VERSION_MAJOR, +# ifdef SIMULATE_VERSION_MINOR + '.', SIMULATE_VERSION_MINOR, +# ifdef SIMULATE_VERSION_PATCH + '.', SIMULATE_VERSION_PATCH, +# ifdef SIMULATE_VERSION_TWEAK + '.', SIMULATE_VERSION_TWEAK, +# endif +# endif +# endif + ']','\0'}; +#endif + +/* Construct the string literal in pieces to prevent the source from + getting matched. Store it in a pointer rather than an array + because some compilers will just produce instructions to fill the + array rather than assigning a pointer to a static array. */ +char const* info_platform = "INFO" ":" "platform[" PLATFORM_ID "]"; +char const* info_arch = "INFO" ":" "arch[" ARCHITECTURE_ID "]"; + + + +#if defined(__INTEL_COMPILER) && defined(_MSVC_LANG) && _MSVC_LANG < 201403L +# if defined(__INTEL_CXX11_MODE__) +# if defined(__cpp_aggregate_nsdmi) +# define CXX_STD 201402L +# else +# define CXX_STD 201103L +# endif +# else +# define CXX_STD 199711L +# endif +#elif defined(_MSC_VER) && defined(_MSVC_LANG) +# define CXX_STD _MSVC_LANG +#else +# define CXX_STD __cplusplus +#endif + +const char* info_language_standard_default = "INFO" ":" "standard_default[" +#if CXX_STD > 202002L + "23" +#elif CXX_STD > 201703L + "20" +#elif CXX_STD >= 201703L + "17" +#elif CXX_STD >= 201402L + "14" +#elif CXX_STD >= 201103L + "11" +#else + "98" +#endif +"]"; + +const char* info_language_extensions_default = "INFO" ":" "extensions_default[" +/* !defined(_MSC_VER) to exclude Clang's MSVC compatibility mode. */ +#if (defined(__clang__) || defined(__GNUC__) || \ + defined(__TI_COMPILER_VERSION__)) && \ + !defined(__STRICT_ANSI__) && !defined(_MSC_VER) + "ON" +#else + "OFF" +#endif +"]"; + +/*--------------------------------------------------------------------------*/ + +int main(int argc, char* argv[]) +{ + int require = 0; + require += info_compiler[argc]; + require += info_platform[argc]; +#ifdef COMPILER_VERSION_MAJOR + require += info_version[argc]; +#endif +#ifdef COMPILER_VERSION_INTERNAL + require += info_version_internal[argc]; +#endif +#ifdef SIMULATE_ID + require += info_simulate[argc]; +#endif +#ifdef SIMULATE_VERSION_MAJOR + require += info_simulate_version[argc]; +#endif +#if defined(__CRAYXT_COMPUTE_LINUX_TARGET) + require += info_cray[argc]; +#endif + require += info_language_standard_default[argc]; + require += info_language_extensions_default[argc]; + (void)argv; + return require; +} diff --git a/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdCXX/a.out b/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdCXX/a.out new file mode 100755 index 0000000..64ddf3c Binary files /dev/null and b/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdCXX/a.out differ diff --git a/rm_arm_control/build/CMakeFiles/CMakeDirectoryInformation.cmake b/rm_arm_control/build/CMakeFiles/CMakeDirectoryInformation.cmake new file mode 100644 index 0000000..e88a8bc --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/CMakeDirectoryInformation.cmake @@ -0,0 +1,16 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 3.22 + +# Relative path conversion top directories. +set(CMAKE_RELATIVE_PATH_TOP_SOURCE "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control") +set(CMAKE_RELATIVE_PATH_TOP_BINARY "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build") + +# Force unix paths in dependencies. +set(CMAKE_FORCE_UNIX_PATHS 1) + + +# The C and CXX include file regular expressions for this directory. +set(CMAKE_C_INCLUDE_REGEX_SCAN "^.*$") +set(CMAKE_C_INCLUDE_REGEX_COMPLAIN "^$") +set(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN}) +set(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN}) diff --git a/rm_arm_control/build/CMakeFiles/CMakeOutput.log b/rm_arm_control/build/CMakeFiles/CMakeOutput.log new file mode 100644 index 0000000..90ec966 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/CMakeOutput.log @@ -0,0 +1,515 @@ +The system is: Linux - 6.8.0-79-generic - x86_64 +Compiling the C compiler identification source file "CMakeCCompilerId.c" succeeded. +Compiler: /usr/bin/cc +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the C compiler identification source "CMakeCCompilerId.c" produced "a.out" + +The C compiler identification is GNU, found in "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdC/a.out" + +Compiling the CXX compiler identification source file "CMakeCXXCompilerId.cpp" succeeded. +Compiler: /usr/bin/c++ +Build flags: +Id flags: + +The output was: +0 + + +Compilation of the CXX compiler identification source "CMakeCXXCompilerId.cpp" produced "a.out" + +The CXX compiler identification is GNU, found in "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/3.22.1/CompilerIdCXX/a.out" + +Detecting C compiler ABI info compiled with the following output: +Change Dir: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp + +Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_8b695/fast && /usr/bin/gmake -f CMakeFiles/cmTC_8b695.dir/build.make CMakeFiles/cmTC_8b695.dir/build +gmake[1]: Entering directory '/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp' +Building C object CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o +/usr/bin/cc -v -o CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c +Using built-in specs. +COLLECT_GCC=/usr/bin/cc +OFFLOAD_TARGET_NAMES=nvptx-none:amdgcn-amdhsa +OFFLOAD_TARGET_DEFAULT=1 +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.2' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --enable-cet --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-nvptx/usr,amdgcn-amdhsa=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-gcn/usr --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=2 +Thread model: posix +Supported LTO compression algorithms: zlib zstd +gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.2) +COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_8b695.dir/' + /usr/lib/gcc/x86_64-linux-gnu/11/cc1 -quiet -v -imultiarch x86_64-linux-gnu /usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c -quiet -dumpdir CMakeFiles/cmTC_8b695.dir/ -dumpbase CMakeCCompilerABI.c.c -dumpbase-ext .c -mtune=generic -march=x86-64 -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccEoB4aa.s +GNU C17 (Ubuntu 11.4.0-1ubuntu1~22.04.2) version 11.4.0 (x86_64-linux-gnu) + compiled by GNU C version 11.4.0, GMP version 6.2.1, MPFR version 4.1.0, MPC version 1.2.1, isl version isl-0.24-GMP + +GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072 +ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu" +ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/11/include-fixed" +ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/11/../../../../x86_64-linux-gnu/include" +#include "..." search starts here: +#include <...> search starts here: + /usr/local/etherlab/include + . + /usr/lib/gcc/x86_64-linux-gnu/11/include + /usr/local/include + /usr/include/x86_64-linux-gnu + /usr/include +End of search list. +GNU C17 (Ubuntu 11.4.0-1ubuntu1~22.04.2) version 11.4.0 (x86_64-linux-gnu) + compiled by GNU C version 11.4.0, GMP version 6.2.1, MPFR version 4.1.0, MPC version 1.2.1, isl version isl-0.24-GMP + +GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072 +Compiler executable checksum: 4011c2103cba78949d7e02d0f0047a3d +COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_8b695.dir/' + as -v --64 -o CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o /tmp/ccEoB4aa.s +GNU assembler version 2.38 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.38 +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/local/etherlab/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/local/etherlab/lib/:./:/usr/lib/gcc/x86_64-linux-gnu/11/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.' +Linking C executable cmTC_8b695 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_8b695.dir/link.txt --verbose=1 +/usr/bin/cc -v CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o -o cmTC_8b695 +Using built-in specs. +COLLECT_GCC=/usr/bin/cc +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper +OFFLOAD_TARGET_NAMES=nvptx-none:amdgcn-amdhsa +OFFLOAD_TARGET_DEFAULT=1 +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.2' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --enable-cet --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-nvptx/usr,amdgcn-amdhsa=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-gcn/usr --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=2 +Thread model: posix +Supported LTO compression algorithms: zlib zstd +gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.2) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/local/etherlab/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/local/etherlab/lib/:./:/usr/lib/gcc/x86_64-linux-gnu/11/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_8b695' '-mtune=generic' '-march=x86-64' '-dumpdir' 'cmTC_8b695.' + /usr/lib/gcc/x86_64-linux-gnu/11/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/11/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper -plugin-opt=-fresolution=/tmp/ccoa3FFN.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_8b695 /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o -L/usr/local/etherlab/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/11 -L/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/local/etherlab/lib -L. -L/usr/lib/gcc/x86_64-linux-gnu/11/../../.. CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_8b695' '-mtune=generic' '-march=x86-64' '-dumpdir' 'cmTC_8b695.' +gmake[1]: Leaving directory '/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp' + + + +Parsed C implicit include dir info from above output: rv=done + found start of include info + found start of implicit include info + add: [/usr/local/etherlab/include] + add: [.] + add: [/usr/lib/gcc/x86_64-linux-gnu/11/include] + add: [/usr/local/include] + add: [/usr/include/x86_64-linux-gnu] + add: [/usr/include] + end of search list found + collapse include dir [/usr/local/etherlab/include] ==> [/usr/local/etherlab/include] + skipping relative include dir [.] + collapse include dir [/usr/lib/gcc/x86_64-linux-gnu/11/include] ==> [/usr/lib/gcc/x86_64-linux-gnu/11/include] + collapse include dir [/usr/local/include] ==> [/usr/local/include] + collapse include dir [/usr/include/x86_64-linux-gnu] ==> [/usr/include/x86_64-linux-gnu] + collapse include dir [/usr/include] ==> [/usr/include] + implicit include dirs: [/usr/local/etherlab/include;/usr/lib/gcc/x86_64-linux-gnu/11/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include] + + +Parsed C implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_8b695/fast && /usr/bin/gmake -f CMakeFiles/cmTC_8b695.dir/build.make CMakeFiles/cmTC_8b695.dir/build] + ignore line: [gmake[1]: Entering directory '/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp'] + ignore line: [Building C object CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o] + ignore line: [/usr/bin/cc -v -o CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o -c /usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/cc] + ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:amdgcn-amdhsa] + ignore line: [OFFLOAD_TARGET_DEFAULT=1] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.2' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --enable-cet --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-nvptx/usr amdgcn-amdhsa=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-gcn/usr --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=2] + ignore line: [Thread model: posix] + ignore line: [Supported LTO compression algorithms: zlib zstd] + ignore line: [gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.2) ] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_8b695.dir/'] + ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/11/cc1 -quiet -v -imultiarch x86_64-linux-gnu /usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c -quiet -dumpdir CMakeFiles/cmTC_8b695.dir/ -dumpbase CMakeCCompilerABI.c.c -dumpbase-ext .c -mtune=generic -march=x86-64 -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccEoB4aa.s] + ignore line: [GNU C17 (Ubuntu 11.4.0-1ubuntu1~22.04.2) version 11.4.0 (x86_64-linux-gnu)] + ignore line: [ compiled by GNU C version 11.4.0 GMP version 6.2.1 MPFR version 4.1.0 MPC version 1.2.1 isl version isl-0.24-GMP] + ignore line: [] + ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072] + ignore line: [ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"] + ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/11/include-fixed"] + ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/11/../../../../x86_64-linux-gnu/include"] + ignore line: [#include "..." search starts here:] + ignore line: [#include <...> search starts here:] + ignore line: [ /usr/local/etherlab/include] + ignore line: [ .] + ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/11/include] + ignore line: [ /usr/local/include] + ignore line: [ /usr/include/x86_64-linux-gnu] + ignore line: [ /usr/include] + ignore line: [End of search list.] + ignore line: [GNU C17 (Ubuntu 11.4.0-1ubuntu1~22.04.2) version 11.4.0 (x86_64-linux-gnu)] + ignore line: [ compiled by GNU C version 11.4.0 GMP version 6.2.1 MPFR version 4.1.0 MPC version 1.2.1 isl version isl-0.24-GMP] + ignore line: [] + ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072] + ignore line: [Compiler executable checksum: 4011c2103cba78949d7e02d0f0047a3d] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_8b695.dir/'] + ignore line: [ as -v --64 -o CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o /tmp/ccEoB4aa.s] + ignore line: [GNU assembler version 2.38 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.38] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/local/etherlab/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/local/etherlab/lib/:./:/usr/lib/gcc/x86_64-linux-gnu/11/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o' '-c' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.'] + ignore line: [Linking C executable cmTC_8b695] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_8b695.dir/link.txt --verbose=1] + ignore line: [/usr/bin/cc -v CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o -o cmTC_8b695 ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/cc] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper] + ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:amdgcn-amdhsa] + ignore line: [OFFLOAD_TARGET_DEFAULT=1] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.2' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --enable-cet --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-nvptx/usr amdgcn-amdhsa=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-gcn/usr --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=2] + ignore line: [Thread model: posix] + ignore line: [Supported LTO compression algorithms: zlib zstd] + ignore line: [gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.2) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/local/etherlab/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/local/etherlab/lib/:./:/usr/lib/gcc/x86_64-linux-gnu/11/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_8b695' '-mtune=generic' '-march=x86-64' '-dumpdir' 'cmTC_8b695.'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/11/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/11/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper -plugin-opt=-fresolution=/tmp/ccoa3FFN.res -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lgcc_s --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_8b695 /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o -L/usr/local/etherlab/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/11 -L/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/local/etherlab/lib -L. -L/usr/lib/gcc/x86_64-linux-gnu/11/../../.. CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o -lgcc --push-state --as-needed -lgcc_s --pop-state -lc -lgcc --push-state --as-needed -lgcc_s --pop-state /usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/collect2] ==> ignore + arg [-plugin] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/11/liblto_plugin.so] ==> ignore + arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper] ==> ignore + arg [-plugin-opt=-fresolution=/tmp/ccoa3FFN.res] ==> ignore + arg [-plugin-opt=-pass-through=-lgcc] ==> ignore + arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore + arg [-plugin-opt=-pass-through=-lc] ==> ignore + arg [-plugin-opt=-pass-through=-lgcc] ==> ignore + arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-pie] ==> ignore + arg [-znow] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTC_8b695] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o] + arg [-L/usr/local/etherlab/lib/../lib] ==> dir [/usr/local/etherlab/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/11] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/11] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/local/etherlab/lib] ==> dir [/usr/local/etherlab/lib] + arg [-L.] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/11/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../..] + arg [CMakeFiles/cmTC_8b695.dir/CMakeCCompilerABI.c.o] ==> ignore + arg [-lgcc] ==> lib [gcc] + arg [--push-state] ==> ignore + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--pop-state] ==> ignore + arg [-lc] ==> lib [c] + arg [-lgcc] ==> lib [gcc] + arg [--push-state] ==> ignore + arg [--as-needed] ==> ignore + arg [-lgcc_s] ==> lib [gcc_s] + arg [--pop-state] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o] + collapse obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o] ==> [/usr/lib/x86_64-linux-gnu/Scrt1.o] + collapse obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o] ==> [/usr/lib/x86_64-linux-gnu/crti.o] + collapse obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o] ==> [/usr/lib/x86_64-linux-gnu/crtn.o] + collapse library dir [/usr/local/etherlab/lib/../lib] ==> [/usr/local/etherlab/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/11] ==> [/usr/lib/gcc/x86_64-linux-gnu/11] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/local/etherlab/lib] ==> [/usr/local/etherlab/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../..] ==> [/usr/lib] + implicit libs: [gcc;gcc_s;c;gcc;gcc_s] + implicit objs: [/usr/lib/x86_64-linux-gnu/Scrt1.o;/usr/lib/x86_64-linux-gnu/crti.o;/usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o;/usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o;/usr/lib/x86_64-linux-gnu/crtn.o] + implicit dirs: [/usr/local/etherlab/lib;/usr/lib/gcc/x86_64-linux-gnu/11;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + +Detecting CXX compiler ABI info compiled with the following output: +Change Dir: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp + +Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_a956b/fast && /usr/bin/gmake -f CMakeFiles/cmTC_a956b.dir/build.make CMakeFiles/cmTC_a956b.dir/build +gmake[1]: Entering directory '/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp' +Building CXX object CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o +/usr/bin/c++ -v -o CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp +Using built-in specs. +COLLECT_GCC=/usr/bin/c++ +OFFLOAD_TARGET_NAMES=nvptx-none:amdgcn-amdhsa +OFFLOAD_TARGET_DEFAULT=1 +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.2' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --enable-cet --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-nvptx/usr,amdgcn-amdhsa=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-gcn/usr --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=2 +Thread model: posix +Supported LTO compression algorithms: zlib zstd +gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.2) +COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_a956b.dir/' + /usr/lib/gcc/x86_64-linux-gnu/11/cc1plus -quiet -v -imultiarch x86_64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpdir CMakeFiles/cmTC_a956b.dir/ -dumpbase CMakeCXXCompilerABI.cpp.cpp -dumpbase-ext .cpp -mtune=generic -march=x86-64 -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccPe1gXB.s +GNU C++17 (Ubuntu 11.4.0-1ubuntu1~22.04.2) version 11.4.0 (x86_64-linux-gnu) + compiled by GNU C version 11.4.0, GMP version 6.2.1, MPFR version 4.1.0, MPC version 1.2.1, isl version isl-0.24-GMP + +GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072 +ignoring duplicate directory "/usr/include/x86_64-linux-gnu/c++/11" +ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu" +ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/11/include-fixed" +ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/11/../../../../x86_64-linux-gnu/include" +#include "..." search starts here: +#include <...> search starts here: + /usr/include/c++/11 + /usr/include/x86_64-linux-gnu/c++/11 + /usr/include/c++/11/backward + /usr/lib/gcc/x86_64-linux-gnu/11/include + /usr/local/include + /usr/include/x86_64-linux-gnu + /usr/include +End of search list. +GNU C++17 (Ubuntu 11.4.0-1ubuntu1~22.04.2) version 11.4.0 (x86_64-linux-gnu) + compiled by GNU C version 11.4.0, GMP version 6.2.1, MPFR version 4.1.0, MPC version 1.2.1, isl version isl-0.24-GMP + +GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072 +Compiler executable checksum: 6c87588fc345655b93b8c25f48f88886 +COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_a956b.dir/' + as -v --64 -o CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o /tmp/ccPe1gXB.s +GNU assembler version 2.38 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.38 +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/local/etherlab/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/local/etherlab/lib/:./:/usr/lib/gcc/x86_64-linux-gnu/11/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.' +Linking CXX executable cmTC_a956b +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_a956b.dir/link.txt --verbose=1 +/usr/bin/c++ -v CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_a956b +Using built-in specs. +COLLECT_GCC=/usr/bin/c++ +COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper +OFFLOAD_TARGET_NAMES=nvptx-none:amdgcn-amdhsa +OFFLOAD_TARGET_DEFAULT=1 +Target: x86_64-linux-gnu +Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.2' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c,ada,c++,go,brig,d,fortran,objc,obj-c++,m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --enable-cet --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32,m64,mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-nvptx/usr,amdgcn-amdhsa=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-gcn/usr --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=2 +Thread model: posix +Supported LTO compression algorithms: zlib zstd +gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.2) +COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/ +LIBRARY_PATH=/usr/local/etherlab/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/local/etherlab/lib/:./:/usr/lib/gcc/x86_64-linux-gnu/11/../../../:/lib/:/usr/lib/ +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_a956b' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'cmTC_a956b.' + /usr/lib/gcc/x86_64-linux-gnu/11/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/11/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper -plugin-opt=-fresolution=/tmp/cctpSNWh.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_a956b /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o -L/usr/local/etherlab/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/11 -L/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/local/etherlab/lib -L. -L/usr/lib/gcc/x86_64-linux-gnu/11/../../.. CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o +COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_a956b' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'cmTC_a956b.' +gmake[1]: Leaving directory '/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp' + + + +Parsed CXX implicit include dir info from above output: rv=done + found start of include info + found start of implicit include info + add: [/usr/include/c++/11] + add: [/usr/include/x86_64-linux-gnu/c++/11] + add: [/usr/include/c++/11/backward] + add: [/usr/lib/gcc/x86_64-linux-gnu/11/include] + add: [/usr/local/include] + add: [/usr/include/x86_64-linux-gnu] + add: [/usr/include] + end of search list found + collapse include dir [/usr/include/c++/11] ==> [/usr/include/c++/11] + collapse include dir [/usr/include/x86_64-linux-gnu/c++/11] ==> [/usr/include/x86_64-linux-gnu/c++/11] + collapse include dir [/usr/include/c++/11/backward] ==> [/usr/include/c++/11/backward] + collapse include dir [/usr/lib/gcc/x86_64-linux-gnu/11/include] ==> [/usr/lib/gcc/x86_64-linux-gnu/11/include] + collapse include dir [/usr/local/include] ==> [/usr/local/include] + collapse include dir [/usr/include/x86_64-linux-gnu] ==> [/usr/include/x86_64-linux-gnu] + collapse include dir [/usr/include] ==> [/usr/include] + implicit include dirs: [/usr/include/c++/11;/usr/include/x86_64-linux-gnu/c++/11;/usr/include/c++/11/backward;/usr/lib/gcc/x86_64-linux-gnu/11/include;/usr/local/include;/usr/include/x86_64-linux-gnu;/usr/include] + + +Parsed CXX implicit link information from above output: + link line regex: [^( *|.*[/\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\]+-)?ld|collect2)[^/\]*( |$)] + ignore line: [Change Dir: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp] + ignore line: [] + ignore line: [Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_a956b/fast && /usr/bin/gmake -f CMakeFiles/cmTC_a956b.dir/build.make CMakeFiles/cmTC_a956b.dir/build] + ignore line: [gmake[1]: Entering directory '/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp'] + ignore line: [Building CXX object CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o] + ignore line: [/usr/bin/c++ -v -o CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o -c /usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/c++] + ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:amdgcn-amdhsa] + ignore line: [OFFLOAD_TARGET_DEFAULT=1] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.2' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --enable-cet --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-nvptx/usr amdgcn-amdhsa=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-gcn/usr --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=2] + ignore line: [Thread model: posix] + ignore line: [Supported LTO compression algorithms: zlib zstd] + ignore line: [gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.2) ] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_a956b.dir/'] + ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/11/cc1plus -quiet -v -imultiarch x86_64-linux-gnu -D_GNU_SOURCE /usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp -quiet -dumpdir CMakeFiles/cmTC_a956b.dir/ -dumpbase CMakeCXXCompilerABI.cpp.cpp -dumpbase-ext .cpp -mtune=generic -march=x86-64 -version -fasynchronous-unwind-tables -fstack-protector-strong -Wformat -Wformat-security -fstack-clash-protection -fcf-protection -o /tmp/ccPe1gXB.s] + ignore line: [GNU C++17 (Ubuntu 11.4.0-1ubuntu1~22.04.2) version 11.4.0 (x86_64-linux-gnu)] + ignore line: [ compiled by GNU C version 11.4.0 GMP version 6.2.1 MPFR version 4.1.0 MPC version 1.2.1 isl version isl-0.24-GMP] + ignore line: [] + ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072] + ignore line: [ignoring duplicate directory "/usr/include/x86_64-linux-gnu/c++/11"] + ignore line: [ignoring nonexistent directory "/usr/local/include/x86_64-linux-gnu"] + ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/11/include-fixed"] + ignore line: [ignoring nonexistent directory "/usr/lib/gcc/x86_64-linux-gnu/11/../../../../x86_64-linux-gnu/include"] + ignore line: [#include "..." search starts here:] + ignore line: [#include <...> search starts here:] + ignore line: [ /usr/include/c++/11] + ignore line: [ /usr/include/x86_64-linux-gnu/c++/11] + ignore line: [ /usr/include/c++/11/backward] + ignore line: [ /usr/lib/gcc/x86_64-linux-gnu/11/include] + ignore line: [ /usr/local/include] + ignore line: [ /usr/include/x86_64-linux-gnu] + ignore line: [ /usr/include] + ignore line: [End of search list.] + ignore line: [GNU C++17 (Ubuntu 11.4.0-1ubuntu1~22.04.2) version 11.4.0 (x86_64-linux-gnu)] + ignore line: [ compiled by GNU C version 11.4.0 GMP version 6.2.1 MPFR version 4.1.0 MPC version 1.2.1 isl version isl-0.24-GMP] + ignore line: [] + ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072] + ignore line: [Compiler executable checksum: 6c87588fc345655b93b8c25f48f88886] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_a956b.dir/'] + ignore line: [ as -v --64 -o CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o /tmp/ccPe1gXB.s] + ignore line: [GNU assembler version 2.38 (x86_64-linux-gnu) using BFD version (GNU Binutils for Ubuntu) 2.38] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/local/etherlab/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/local/etherlab/lib/:./:/usr/lib/gcc/x86_64-linux-gnu/11/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o' '-c' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.'] + ignore line: [Linking CXX executable cmTC_a956b] + ignore line: [/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_a956b.dir/link.txt --verbose=1] + ignore line: [/usr/bin/c++ -v CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o -o cmTC_a956b ] + ignore line: [Using built-in specs.] + ignore line: [COLLECT_GCC=/usr/bin/c++] + ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper] + ignore line: [OFFLOAD_TARGET_NAMES=nvptx-none:amdgcn-amdhsa] + ignore line: [OFFLOAD_TARGET_DEFAULT=1] + ignore line: [Target: x86_64-linux-gnu] + ignore line: [Configured with: ../src/configure -v --with-pkgversion='Ubuntu 11.4.0-1ubuntu1~22.04.2' --with-bugurl=file:///usr/share/doc/gcc-11/README.Bugs --enable-languages=c ada c++ go brig d fortran objc obj-c++ m2 --prefix=/usr --with-gcc-major-version-only --program-suffix=-11 --program-prefix=x86_64-linux-gnu- --enable-shared --enable-linker-build-id --libexecdir=/usr/lib --without-included-gettext --enable-threads=posix --libdir=/usr/lib --enable-nls --enable-bootstrap --enable-clocale=gnu --enable-libstdcxx-debug --enable-libstdcxx-time=yes --with-default-libstdcxx-abi=new --enable-gnu-unique-object --disable-vtable-verify --enable-plugin --enable-default-pie --with-system-zlib --enable-libphobos-checking=release --with-target-system-zlib=auto --enable-objc-gc=auto --enable-multiarch --disable-werror --enable-cet --with-arch-32=i686 --with-abi=m64 --with-multilib-list=m32 m64 mx32 --enable-multilib --with-tune=generic --enable-offload-targets=nvptx-none=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-nvptx/usr amdgcn-amdhsa=/build/gcc-11-2Y5pKs/gcc-11-11.4.0/debian/tmp-gcn/usr --without-cuda-driver --enable-checking=release --build=x86_64-linux-gnu --host=x86_64-linux-gnu --target=x86_64-linux-gnu --with-build-config=bootstrap-lto-lean --enable-link-serialization=2] + ignore line: [Thread model: posix] + ignore line: [Supported LTO compression algorithms: zlib zstd] + ignore line: [gcc version 11.4.0 (Ubuntu 11.4.0-1ubuntu1~22.04.2) ] + ignore line: [COMPILER_PATH=/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/] + ignore line: [LIBRARY_PATH=/usr/local/etherlab/lib/../lib/:/usr/lib/gcc/x86_64-linux-gnu/11/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/:/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib/:/lib/x86_64-linux-gnu/:/lib/../lib/:/usr/lib/x86_64-linux-gnu/:/usr/lib/../lib/:/usr/local/etherlab/lib/:./:/usr/lib/gcc/x86_64-linux-gnu/11/../../../:/lib/:/usr/lib/] + ignore line: [COLLECT_GCC_OPTIONS='-v' '-o' 'cmTC_a956b' '-shared-libgcc' '-mtune=generic' '-march=x86-64' '-dumpdir' 'cmTC_a956b.'] + link line: [ /usr/lib/gcc/x86_64-linux-gnu/11/collect2 -plugin /usr/lib/gcc/x86_64-linux-gnu/11/liblto_plugin.so -plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper -plugin-opt=-fresolution=/tmp/cctpSNWh.res -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc -plugin-opt=-pass-through=-lc -plugin-opt=-pass-through=-lgcc_s -plugin-opt=-pass-through=-lgcc --build-id --eh-frame-hdr -m elf_x86_64 --hash-style=gnu --as-needed -dynamic-linker /lib64/ld-linux-x86-64.so.2 -pie -z now -z relro -o cmTC_a956b /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o /usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o -L/usr/local/etherlab/lib/../lib -L/usr/lib/gcc/x86_64-linux-gnu/11 -L/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu -L/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib -L/lib/x86_64-linux-gnu -L/lib/../lib -L/usr/lib/x86_64-linux-gnu -L/usr/lib/../lib -L/usr/local/etherlab/lib -L. -L/usr/lib/gcc/x86_64-linux-gnu/11/../../.. CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o -lstdc++ -lm -lgcc_s -lgcc -lc -lgcc_s -lgcc /usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o /usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/collect2] ==> ignore + arg [-plugin] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/11/liblto_plugin.so] ==> ignore + arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/11/lto-wrapper] ==> ignore + arg [-plugin-opt=-fresolution=/tmp/cctpSNWh.res] ==> ignore + arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore + arg [-plugin-opt=-pass-through=-lgcc] ==> ignore + arg [-plugin-opt=-pass-through=-lc] ==> ignore + arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore + arg [-plugin-opt=-pass-through=-lgcc] ==> ignore + arg [--build-id] ==> ignore + arg [--eh-frame-hdr] ==> ignore + arg [-m] ==> ignore + arg [elf_x86_64] ==> ignore + arg [--hash-style=gnu] ==> ignore + arg [--as-needed] ==> ignore + arg [-dynamic-linker] ==> ignore + arg [/lib64/ld-linux-x86-64.so.2] ==> ignore + arg [-pie] ==> ignore + arg [-znow] ==> ignore + arg [-zrelro] ==> ignore + arg [-o] ==> ignore + arg [cmTC_a956b] ==> ignore + arg [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o] + arg [-L/usr/local/etherlab/lib/../lib] ==> dir [/usr/local/etherlab/lib/../lib] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/11] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/11] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu] + arg [-L/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib] + arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu] + arg [-L/lib/../lib] ==> dir [/lib/../lib] + arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu] + arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib] + arg [-L/usr/local/etherlab/lib] ==> dir [/usr/local/etherlab/lib] + arg [-L.] ==> ignore + arg [-L/usr/lib/gcc/x86_64-linux-gnu/11/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../..] + arg [CMakeFiles/cmTC_a956b.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore + arg [-lstdc++] ==> lib [stdc++] + arg [-lm] ==> lib [m] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [-lc] ==> lib [c] + arg [-lgcc_s] ==> lib [gcc_s] + arg [-lgcc] ==> lib [gcc] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o] + arg [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o] ==> obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o] + collapse obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/Scrt1.o] ==> [/usr/lib/x86_64-linux-gnu/Scrt1.o] + collapse obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crti.o] ==> [/usr/lib/x86_64-linux-gnu/crti.o] + collapse obj [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu/crtn.o] ==> [/usr/lib/x86_64-linux-gnu/crtn.o] + collapse library dir [/usr/local/etherlab/lib/../lib] ==> [/usr/local/etherlab/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/11] ==> [/usr/lib/gcc/x86_64-linux-gnu/11] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../../../lib] ==> [/usr/lib] + collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu] + collapse library dir [/lib/../lib] ==> [/lib] + collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu] + collapse library dir [/usr/lib/../lib] ==> [/usr/lib] + collapse library dir [/usr/local/etherlab/lib] ==> [/usr/local/etherlab/lib] + collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/11/../../..] ==> [/usr/lib] + implicit libs: [stdc++;m;gcc_s;gcc;c;gcc_s;gcc] + implicit objs: [/usr/lib/x86_64-linux-gnu/Scrt1.o;/usr/lib/x86_64-linux-gnu/crti.o;/usr/lib/gcc/x86_64-linux-gnu/11/crtbeginS.o;/usr/lib/gcc/x86_64-linux-gnu/11/crtendS.o;/usr/lib/x86_64-linux-gnu/crtn.o] + implicit dirs: [/usr/local/etherlab/lib;/usr/lib/gcc/x86_64-linux-gnu/11;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib] + implicit fwks: [] + + +Determining if the include file pthread.h exists passed with the following output: +Change Dir: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp + +Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_27334/fast && /usr/bin/gmake -f CMakeFiles/cmTC_27334.dir/build.make CMakeFiles/cmTC_27334.dir/build +gmake[1]: 进入目录“/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp” +Building C object CMakeFiles/cmTC_27334.dir/CheckIncludeFile.c.o +/usr/bin/cc -std=gnu11 -o CMakeFiles/cmTC_27334.dir/CheckIncludeFile.c.o -c /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp/CheckIncludeFile.c +Linking C executable cmTC_27334 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_27334.dir/link.txt --verbose=1 +/usr/bin/cc CMakeFiles/cmTC_27334.dir/CheckIncludeFile.c.o -o cmTC_27334 +gmake[1]: 离开目录“/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp” + + + +Performing C SOURCE FILE Test CMAKE_HAVE_LIBC_PTHREAD succeeded with the following output: +Change Dir: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp + +Run Build Command(s):/usr/bin/gmake -f Makefile cmTC_73ce1/fast && /usr/bin/gmake -f CMakeFiles/cmTC_73ce1.dir/build.make CMakeFiles/cmTC_73ce1.dir/build +gmake[1]: 进入目录“/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp” +Building C object CMakeFiles/cmTC_73ce1.dir/src.c.o +/usr/bin/cc -DCMAKE_HAVE_LIBC_PTHREAD -std=gnu11 -o CMakeFiles/cmTC_73ce1.dir/src.c.o -c /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp/src.c +Linking C executable cmTC_73ce1 +/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_73ce1.dir/link.txt --verbose=1 +/usr/bin/cc CMakeFiles/cmTC_73ce1.dir/src.c.o -o cmTC_73ce1 +gmake[1]: 离开目录“/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/CMakeTmp” + + +Source file was: +#include + +static void* test_func(void* data) +{ + return data; +} + +int main(void) +{ + pthread_t thread; + pthread_create(&thread, NULL, test_func, NULL); + pthread_detach(thread); + pthread_cancel(thread); + pthread_join(thread, NULL); + pthread_atfork(NULL, NULL, NULL); + pthread_exit(NULL); + + return 0; +} + diff --git a/rm_arm_control/build/CMakeFiles/CMakeRuleHashes.txt b/rm_arm_control/build/CMakeFiles/CMakeRuleHashes.txt new file mode 100644 index 0000000..a4f8561 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/CMakeRuleHashes.txt @@ -0,0 +1,2 @@ +# Hashes of file build rules. +036f7cafecdbf65613125238ad6a1ad5 CMakeFiles/rm_arm_control_uninstall diff --git a/rm_arm_control/build/CMakeFiles/Makefile.cmake b/rm_arm_control/build/CMakeFiles/Makefile.cmake new file mode 100644 index 0000000..6eb723e --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/Makefile.cmake @@ -0,0 +1,844 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 3.22 + +# The generator used is: +set(CMAKE_DEPENDS_GENERATOR "Unix Makefiles") + +# The top level Makefile was generated from the following files: +set(CMAKE_MAKEFILE_DEPENDS + "CMakeCache.txt" + "../CMakeLists.txt" + "CMakeFiles/3.22.1/CMakeCCompiler.cmake" + "CMakeFiles/3.22.1/CMakeCXXCompiler.cmake" + "CMakeFiles/3.22.1/CMakeSystem.cmake" + "ament_cmake_core/package.cmake" + "ament_cmake_package_templates/templates.cmake" + "../package.xml" + "/opt/ros/humble/cmake/yamlConfig.cmake" + "/opt/ros/humble/cmake/yamlConfigVersion.cmake" + "/opt/ros/humble/cmake/yamlTargets-none.cmake" + "/opt/ros/humble/cmake/yamlTargets.cmake" + "/opt/ros/humble/lib/cmake/fastcdr/fastcdr-config-version.cmake" + "/opt/ros/humble/lib/cmake/fastcdr/fastcdr-config.cmake" + "/opt/ros/humble/lib/cmake/fastcdr/fastcdr-dynamic-targets-none.cmake" + "/opt/ros/humble/lib/cmake/fastcdr/fastcdr-dynamic-targets.cmake" + "/opt/ros/humble/lib/foonathan_memory/cmake/foonathan_memory-config-none.cmake" + "/opt/ros/humble/lib/foonathan_memory/cmake/foonathan_memory-config-version.cmake" + "/opt/ros/humble/lib/foonathan_memory/cmake/foonathan_memory-config.cmake" + "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/package_level/local_setup.bash.in" + "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/package_level/local_setup.sh.in" + "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/package_level/local_setup.zsh.in" + "/opt/ros/humble/share/action_msgs/cmake/action_msgsConfig-version.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgsConfig.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/action_msgs/cmake/action_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/action_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/action_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/action_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/action_msgs/cmake/export_action_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/action_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/action_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/action_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/ament_cmake/cmake/ament_cmakeConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake/cmake/ament_cmakeConfig.cmake" + "/opt/ros/humble/share/ament_cmake/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_core-extras.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_coreConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_coreConfig.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_environment-extras.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_environment_hooks-extras.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_index-extras.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_package_templates-extras.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_symlink_install-extras.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/ament_cmake_uninstall_target-extras.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/all.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/ament_execute_extensions.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/ament_package.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/ament_package_xml.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/ament_register_extension.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/assert_file_exists.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/get_executable_path.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/list_append_unique.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/normalize_path.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/package_xml_2_cmake.py" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/python.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/stamp.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/string_ends_with.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/templates/nameConfig-version.cmake.in" + "/opt/ros/humble/share/ament_cmake_core/cmake/core/templates/nameConfig.cmake.in" + "/opt/ros/humble/share/ament_cmake_core/cmake/environment/ament_cmake_environment_package_hook.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/environment/ament_generate_environment.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/environment_hooks/ament_cmake_environment_hooks_package_hook.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/environment_hooks/ament_environment_hooks.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/environment_hooks/ament_generate_package_environment.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh" + "/opt/ros/humble/share/ament_cmake_core/cmake/environment_hooks/environment/path.sh" + "/opt/ros/humble/share/ament_cmake_core/cmake/index/ament_cmake_index_package_hook.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/index/ament_index_get_prefix_path.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/index/ament_index_get_resource.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/index/ament_index_get_resources.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/index/ament_index_has_resource.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/index/ament_index_register_package.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/index/ament_index_register_resource.cmake" + "/opt/ros/humble/share/ament_cmake_core/cmake/package_templates/templates_2_cmake.py" + "/opt/ros/humble/share/ament_cmake_core/cmake/uninstall_target/ament_cmake_uninstall_target.cmake.in" + "/opt/ros/humble/share/ament_cmake_core/cmake/uninstall_target/ament_cmake_uninstall_target_append_uninstall_code.cmake" + "/opt/ros/humble/share/ament_cmake_export_definitions/cmake/ament_cmake_export_definitions-extras.cmake" + "/opt/ros/humble/share/ament_cmake_export_definitions/cmake/ament_cmake_export_definitionsConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_export_definitions/cmake/ament_cmake_export_definitionsConfig.cmake" + "/opt/ros/humble/share/ament_cmake_export_definitions/cmake/ament_export_definitions.cmake" + "/opt/ros/humble/share/ament_cmake_export_dependencies/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/ament_cmake_export_dependencies/cmake/ament_cmake_export_dependenciesConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_export_dependencies/cmake/ament_cmake_export_dependenciesConfig.cmake" + "/opt/ros/humble/share/ament_cmake_export_dependencies/cmake/ament_export_dependencies.cmake" + "/opt/ros/humble/share/ament_cmake_export_include_directories/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/ament_cmake_export_include_directories/cmake/ament_cmake_export_include_directoriesConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_export_include_directories/cmake/ament_cmake_export_include_directoriesConfig.cmake" + "/opt/ros/humble/share/ament_cmake_export_include_directories/cmake/ament_export_include_directories.cmake" + "/opt/ros/humble/share/ament_cmake_export_interfaces/cmake/ament_cmake_export_interfaces-extras.cmake" + "/opt/ros/humble/share/ament_cmake_export_interfaces/cmake/ament_cmake_export_interfacesConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_export_interfaces/cmake/ament_cmake_export_interfacesConfig.cmake" + "/opt/ros/humble/share/ament_cmake_export_interfaces/cmake/ament_export_interfaces.cmake" + "/opt/ros/humble/share/ament_cmake_export_libraries/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/ament_cmake_export_libraries/cmake/ament_cmake_export_librariesConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_export_libraries/cmake/ament_cmake_export_librariesConfig.cmake" + "/opt/ros/humble/share/ament_cmake_export_libraries/cmake/ament_export_libraries.cmake" + "/opt/ros/humble/share/ament_cmake_export_libraries/cmake/ament_export_library_names.cmake" + "/opt/ros/humble/share/ament_cmake_export_link_flags/cmake/ament_cmake_export_link_flags-extras.cmake" + "/opt/ros/humble/share/ament_cmake_export_link_flags/cmake/ament_cmake_export_link_flagsConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_export_link_flags/cmake/ament_cmake_export_link_flagsConfig.cmake" + "/opt/ros/humble/share/ament_cmake_export_link_flags/cmake/ament_export_link_flags.cmake" + "/opt/ros/humble/share/ament_cmake_export_targets/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/ament_cmake_export_targets/cmake/ament_cmake_export_targetsConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_export_targets/cmake/ament_cmake_export_targetsConfig.cmake" + "/opt/ros/humble/share/ament_cmake_export_targets/cmake/ament_export_targets.cmake" + "/opt/ros/humble/share/ament_cmake_gen_version_h/cmake/ament_cmake_gen_version_h-extras.cmake" + "/opt/ros/humble/share/ament_cmake_gen_version_h/cmake/ament_cmake_gen_version_h.cmake" + "/opt/ros/humble/share/ament_cmake_gen_version_h/cmake/ament_cmake_gen_version_hConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_gen_version_h/cmake/ament_cmake_gen_version_hConfig.cmake" + "/opt/ros/humble/share/ament_cmake_gen_version_h/cmake/ament_generate_version_header.cmake" + "/opt/ros/humble/share/ament_cmake_include_directories/cmake/ament_cmake_include_directories-extras.cmake" + "/opt/ros/humble/share/ament_cmake_include_directories/cmake/ament_cmake_include_directoriesConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_include_directories/cmake/ament_cmake_include_directoriesConfig.cmake" + "/opt/ros/humble/share/ament_cmake_include_directories/cmake/ament_include_directories_order.cmake" + "/opt/ros/humble/share/ament_cmake_libraries/cmake/ament_cmake_libraries-extras.cmake" + "/opt/ros/humble/share/ament_cmake_libraries/cmake/ament_cmake_librariesConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_libraries/cmake/ament_cmake_librariesConfig.cmake" + "/opt/ros/humble/share/ament_cmake_libraries/cmake/ament_libraries_deduplicate.cmake" + "/opt/ros/humble/share/ament_cmake_python/cmake/ament_cmake_python-extras.cmake" + "/opt/ros/humble/share/ament_cmake_python/cmake/ament_cmake_pythonConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_python/cmake/ament_cmake_pythonConfig.cmake" + "/opt/ros/humble/share/ament_cmake_python/cmake/ament_get_python_install_dir.cmake" + "/opt/ros/humble/share/ament_cmake_python/cmake/ament_python_install_module.cmake" + "/opt/ros/humble/share/ament_cmake_python/cmake/ament_python_install_package.cmake" + "/opt/ros/humble/share/ament_cmake_target_dependencies/cmake/ament_cmake_target_dependencies-extras.cmake" + "/opt/ros/humble/share/ament_cmake_target_dependencies/cmake/ament_cmake_target_dependenciesConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_target_dependencies/cmake/ament_cmake_target_dependenciesConfig.cmake" + "/opt/ros/humble/share/ament_cmake_target_dependencies/cmake/ament_get_recursive_properties.cmake" + "/opt/ros/humble/share/ament_cmake_target_dependencies/cmake/ament_target_dependencies.cmake" + "/opt/ros/humble/share/ament_cmake_test/cmake/ament_add_test.cmake" + "/opt/ros/humble/share/ament_cmake_test/cmake/ament_add_test_label.cmake" + "/opt/ros/humble/share/ament_cmake_test/cmake/ament_cmake_test-extras.cmake" + "/opt/ros/humble/share/ament_cmake_test/cmake/ament_cmake_testConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_test/cmake/ament_cmake_testConfig.cmake" + "/opt/ros/humble/share/ament_cmake_version/cmake/ament_cmake_version-extras.cmake" + "/opt/ros/humble/share/ament_cmake_version/cmake/ament_cmake_versionConfig-version.cmake" + "/opt/ros/humble/share/ament_cmake_version/cmake/ament_cmake_versionConfig.cmake" + "/opt/ros/humble/share/ament_cmake_version/cmake/ament_export_development_version_if_higher_than_manifest.cmake" + "/opt/ros/humble/share/ament_index_cpp/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/ament_index_cpp/cmake/ament_index_cppConfig-version.cmake" + "/opt/ros/humble/share/ament_index_cpp/cmake/ament_index_cppConfig.cmake" + "/opt/ros/humble/share/ament_index_cpp/cmake/export_ament_index_cppExport-none.cmake" + "/opt/ros/humble/share/ament_index_cpp/cmake/export_ament_index_cppExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfacesConfig-version.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfacesConfig.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfaces__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfaces__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfaces__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfaces__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfaces__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfaces__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfaces__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/builtin_interfaces__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/export_builtin_interfaces__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/builtin_interfaces/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/control_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/control_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/control_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/control_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgsConfig-version.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgsConfig.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/control_msgs/cmake/control_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/control_msgs/cmake/export_control_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/control_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/control_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/control_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/fastrtps/cmake/fast-discovery-server-targets-none.cmake" + "/opt/ros/humble/share/fastrtps/cmake/fast-discovery-server-targets.cmake" + "/opt/ros/humble/share/fastrtps/cmake/fastrtps-config-version.cmake" + "/opt/ros/humble/share/fastrtps/cmake/fastrtps-config.cmake" + "/opt/ros/humble/share/fastrtps/cmake/fastrtps-dynamic-targets-none.cmake" + "/opt/ros/humble/share/fastrtps/cmake/fastrtps-dynamic-targets.cmake" + "/opt/ros/humble/share/fastrtps/cmake/optionparser-targets.cmake" + "/opt/ros/humble/share/fastrtps_cmake_module/cmake/Modules/FindFastRTPS.cmake" + "/opt/ros/humble/share/fastrtps_cmake_module/cmake/fastrtps_cmake_module-extras.cmake" + "/opt/ros/humble/share/fastrtps_cmake_module/cmake/fastrtps_cmake_moduleConfig-version.cmake" + "/opt/ros/humble/share/fastrtps_cmake_module/cmake/fastrtps_cmake_moduleConfig.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/export_geometry_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgsConfig-version.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgsConfig.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/geometry_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/geometry_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/libstatistics_collectorConfig-version.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/libstatistics_collectorConfig.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/libstatistics_collectorExport-none.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/libstatistics_collectorExport.cmake" + "/opt/ros/humble/share/libstatistics_collector/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/libyaml_vendor/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/libyaml_vendor/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/libyaml_vendor/cmake/libyaml_vendor-extras.cmake" + "/opt/ros/humble/share/libyaml_vendor/cmake/libyaml_vendorConfig-version.cmake" + "/opt/ros/humble/share/libyaml_vendor/cmake/libyaml_vendorConfig.cmake" + "/opt/ros/humble/share/rcl/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rcl/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rcl/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rcl/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rcl/cmake/rcl-extras.cmake" + "/opt/ros/humble/share/rcl/cmake/rclConfig-version.cmake" + "/opt/ros/humble/share/rcl/cmake/rclConfig.cmake" + "/opt/ros/humble/share/rcl/cmake/rclExport-none.cmake" + "/opt/ros/humble/share/rcl/cmake/rclExport.cmake" + "/opt/ros/humble/share/rcl/cmake/rcl_set_symbol_visibility_hidden.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/export_rcl_interfaces__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfacesConfig-version.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfacesConfig.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfaces__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfaces__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfaces__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfaces__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfaces__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfaces__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfaces__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rcl_interfaces__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/rcl_interfaces/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/rcl_logging_interface/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rcl_logging_interface/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rcl_logging_interface/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rcl_logging_interface/cmake/rcl_logging_interfaceConfig-version.cmake" + "/opt/ros/humble/share/rcl_logging_interface/cmake/rcl_logging_interfaceConfig.cmake" + "/opt/ros/humble/share/rcl_logging_interface/cmake/rcl_logging_interfaceExport-none.cmake" + "/opt/ros/humble/share/rcl_logging_interface/cmake/rcl_logging_interfaceExport.cmake" + "/opt/ros/humble/share/rcl_logging_spdlog/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rcl_logging_spdlog/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rcl_logging_spdlog/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rcl_logging_spdlog/cmake/rcl_logging_spdlogConfig-version.cmake" + "/opt/ros/humble/share/rcl_logging_spdlog/cmake/rcl_logging_spdlogConfig.cmake" + "/opt/ros/humble/share/rcl_logging_spdlog/cmake/rcl_logging_spdlogExport-none.cmake" + "/opt/ros/humble/share/rcl_logging_spdlog/cmake/rcl_logging_spdlogExport.cmake" + "/opt/ros/humble/share/rcl_yaml_param_parser/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rcl_yaml_param_parser/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rcl_yaml_param_parser/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rcl_yaml_param_parser/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rcl_yaml_param_parser/cmake/rcl_yaml_param_parserConfig-version.cmake" + "/opt/ros/humble/share/rcl_yaml_param_parser/cmake/rcl_yaml_param_parserConfig.cmake" + "/opt/ros/humble/share/rcl_yaml_param_parser/cmake/rcl_yaml_param_parserExport-none.cmake" + "/opt/ros/humble/share/rcl_yaml_param_parser/cmake/rcl_yaml_param_parserExport.cmake" + "/opt/ros/humble/share/rclcpp/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rclcpp/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rclcpp/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rclcpp/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rclcpp/cmake/rclcppConfig-version.cmake" + "/opt/ros/humble/share/rclcpp/cmake/rclcppConfig.cmake" + "/opt/ros/humble/share/rclcpp/cmake/rclcppExport-none.cmake" + "/opt/ros/humble/share/rclcpp/cmake/rclcppExport.cmake" + "/opt/ros/humble/share/rcpputils/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rcpputils/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rcpputils/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rcpputils/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rcpputils/cmake/rcpputilsConfig-version.cmake" + "/opt/ros/humble/share/rcpputils/cmake/rcpputilsConfig.cmake" + "/opt/ros/humble/share/rcpputils/cmake/rcpputilsExport-none.cmake" + "/opt/ros/humble/share/rcpputils/cmake/rcpputilsExport.cmake" + "/opt/ros/humble/share/rcutils/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rcutils/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rcutils/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rcutils/cmake/ament_cmake_export_link_flags-extras.cmake" + "/opt/ros/humble/share/rcutils/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rcutils/cmake/rcutilsConfig-version.cmake" + "/opt/ros/humble/share/rcutils/cmake/rcutilsConfig.cmake" + "/opt/ros/humble/share/rcutils/cmake/rcutilsExport-none.cmake" + "/opt/ros/humble/share/rcutils/cmake/rcutilsExport.cmake" + "/opt/ros/humble/share/rmw/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rmw/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rmw/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rmw/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rmw/cmake/configure_rmw_library.cmake" + "/opt/ros/humble/share/rmw/cmake/get_rmw_typesupport.cmake" + "/opt/ros/humble/share/rmw/cmake/register_rmw_implementation.cmake" + "/opt/ros/humble/share/rmw/cmake/rmw-extras.cmake" + "/opt/ros/humble/share/rmw/cmake/rmwConfig-version.cmake" + "/opt/ros/humble/share/rmw/cmake/rmwConfig.cmake" + "/opt/ros/humble/share/rmw/cmake/rmwExport-none.cmake" + "/opt/ros/humble/share/rmw/cmake/rmwExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/export_rmw_dds_common__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_commonConfig-version.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_commonConfig.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common_libraryExport-none.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rmw_dds_common_libraryExport.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/rmw_dds_common/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_cpp/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_cpp/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_cpp/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_cpp/cmake/rmw_fastrtps_cpp-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_cpp/cmake/rmw_fastrtps_cppConfig-version.cmake" + "/opt/ros/humble/share/rmw_fastrtps_cpp/cmake/rmw_fastrtps_cppConfig.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/rmw_fastrtps_shared_cpp-extras.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/rmw_fastrtps_shared_cppConfig-version.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/rmw_fastrtps_shared_cppConfig.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/rmw_fastrtps_shared_cppExport-none.cmake" + "/opt/ros/humble/share/rmw_fastrtps_shared_cpp/cmake/rmw_fastrtps_shared_cppExport.cmake" + "/opt/ros/humble/share/rmw_implementation/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rmw_implementation/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rmw_implementation/cmake/export_rmw_implementationExport-none.cmake" + "/opt/ros/humble/share/rmw_implementation/cmake/export_rmw_implementationExport.cmake" + "/opt/ros/humble/share/rmw_implementation/cmake/rmw_implementation-extras.cmake" + "/opt/ros/humble/share/rmw_implementation/cmake/rmw_implementationConfig-version.cmake" + "/opt/ros/humble/share/rmw_implementation/cmake/rmw_implementationConfig.cmake" + "/opt/ros/humble/share/rmw_implementation_cmake/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rmw_implementation_cmake/cmake/call_for_each_rmw_implementation.cmake" + "/opt/ros/humble/share/rmw_implementation_cmake/cmake/get_available_rmw_implementations.cmake" + "/opt/ros/humble/share/rmw_implementation_cmake/cmake/get_default_rmw_implementation.cmake" + "/opt/ros/humble/share/rmw_implementation_cmake/cmake/rmw_implementation_cmake-extras.cmake" + "/opt/ros/humble/share/rmw_implementation_cmake/cmake/rmw_implementation_cmakeConfig-version.cmake" + "/opt/ros/humble/share/rmw_implementation_cmake/cmake/rmw_implementation_cmakeConfig.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/export_rosgraph_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgsConfig-version.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgsConfig.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosgraph_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/rosgraph_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_adapter/cmake/rosidl_adapt_interfaces.cmake" + "/opt/ros/humble/share/rosidl_adapter/cmake/rosidl_adapter-extras.cmake" + "/opt/ros/humble/share/rosidl_adapter/cmake/rosidl_adapterConfig-version.cmake" + "/opt/ros/humble/share/rosidl_adapter/cmake/rosidl_adapterConfig.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_cmakeConfig-version.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_cmakeConfig.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_export_typesupport_libraries.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_export_typesupport_targets.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_generate_interfaces.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_get_typesupport_target.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_target_interfaces.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/rosidl_write_generator_arguments.cmake" + "/opt/ros/humble/share/rosidl_cmake/cmake/string_camel_case_to_lower_case_underscore.cmake" + "/opt/ros/humble/share/rosidl_default_runtime/cmake/rosidl_default_runtime-extras.cmake" + "/opt/ros/humble/share/rosidl_default_runtime/cmake/rosidl_default_runtimeConfig-version.cmake" + "/opt/ros/humble/share/rosidl_default_runtime/cmake/rosidl_default_runtimeConfig.cmake" + "/opt/ros/humble/share/rosidl_generator_c/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_generator_c/cmake/register_c.cmake" + "/opt/ros/humble/share/rosidl_generator_c/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/rosidl_generator_c/cmake/rosidl_generator_c-extras.cmake" + "/opt/ros/humble/share/rosidl_generator_c/cmake/rosidl_generator_cConfig-version.cmake" + "/opt/ros/humble/share/rosidl_generator_c/cmake/rosidl_generator_cConfig.cmake" + "/opt/ros/humble/share/rosidl_generator_cpp/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_generator_cpp/cmake/register_cpp.cmake" + "/opt/ros/humble/share/rosidl_generator_cpp/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/rosidl_generator_cpp/cmake/rosidl_generator_cpp-extras.cmake" + "/opt/ros/humble/share/rosidl_generator_cpp/cmake/rosidl_generator_cppConfig-version.cmake" + "/opt/ros/humble/share/rosidl_generator_cpp/cmake/rosidl_generator_cppConfig.cmake" + "/opt/ros/humble/share/rosidl_runtime_c/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_runtime_c/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_runtime_c/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rosidl_runtime_c/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_runtime_c/cmake/rosidl_runtime_cConfig-version.cmake" + "/opt/ros/humble/share/rosidl_runtime_c/cmake/rosidl_runtime_cConfig.cmake" + "/opt/ros/humble/share/rosidl_runtime_c/cmake/rosidl_runtime_cExport-none.cmake" + "/opt/ros/humble/share/rosidl_runtime_c/cmake/rosidl_runtime_cExport.cmake" + "/opt/ros/humble/share/rosidl_runtime_cpp/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_runtime_cpp/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_runtime_cpp/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_runtime_cpp/cmake/rosidl_runtime_cppConfig-version.cmake" + "/opt/ros/humble/share/rosidl_runtime_cpp/cmake/rosidl_runtime_cppConfig.cmake" + "/opt/ros/humble/share/rosidl_runtime_cpp/cmake/rosidl_runtime_cppExport.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/get_used_typesupports.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/rosidl_typesupport_c-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/rosidl_typesupport_cConfig-version.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/rosidl_typesupport_cConfig.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/rosidl_typesupport_c/cmake/rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/rosidl_typesupport_cpp-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/rosidl_typesupport_cppConfig-version.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/rosidl_typesupport_cppConfig.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/rosidl_typesupport_cpp/cmake/rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/rosidl_typesupport_fastrtps_c-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/rosidl_typesupport_fastrtps_cConfig-version.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/rosidl_typesupport_fastrtps_cConfig.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_c/cmake/rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/rosidl_typesupport_fastrtps_cpp-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/rosidl_typesupport_fastrtps_cppConfig-version.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/rosidl_typesupport_fastrtps_cppConfig.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/rosidl_typesupport_fastrtps_cpp/cmake/rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/rosidl_typesupport_interface/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_interface/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_interface/cmake/rosidl_typesupport_interfaceConfig-version.cmake" + "/opt/ros/humble/share/rosidl_typesupport_interface/cmake/rosidl_typesupport_interfaceConfig.cmake" + "/opt/ros/humble/share/rosidl_typesupport_interface/cmake/rosidl_typesupport_interfaceExport.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/rosidl_typesupport_introspection_c-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/rosidl_typesupport_introspection_cConfig-version.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/rosidl_typesupport_introspection_cConfig.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_c/cmake/rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/rosidl_typesupport_introspection_cpp-extras.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/rosidl_typesupport_introspection_cppConfig-version.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/rosidl_typesupport_introspection_cppConfig.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/rosidl_typesupport_introspection_cpp/cmake/rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgsExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/export_sensor_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgsConfig-version.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgsConfig.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/sensor_msgs/cmake/sensor_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/spdlog_vendor/cmake/spdlog_vendorConfig-version.cmake" + "/opt/ros/humble/share/spdlog_vendor/cmake/spdlog_vendorConfig.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/export_statistics_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgsConfig-version.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgsConfig.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/statistics_msgs/cmake/statistics_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/std_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/std_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/std_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/std_msgs/cmake/export_std_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/std_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/std_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgsConfig-version.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgsConfig.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/std_msgs/cmake/std_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/tracetools/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/tracetools/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/tracetools/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/tracetools/cmake/tracetoolsConfig-version.cmake" + "/opt/ros/humble/share/tracetools/cmake/tracetoolsConfig.cmake" + "/opt/ros/humble/share/tracetools/cmake/tracetools_exportExport-none.cmake" + "/opt/ros/humble/share/tracetools/cmake/tracetools_exportExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/export_trajectory_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgsConfig-version.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgsConfig.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/trajectory_msgs/cmake/trajectory_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/ament_cmake_export_dependencies-extras.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/ament_cmake_export_include_directories-extras.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/ament_cmake_export_libraries-extras.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/ament_cmake_export_targets-extras.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_generator_cExport-none.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_generator_cExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_generator_cppExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_generator_pyExport-none.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_generator_pyExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_typesupport_fastrtps_cExport-none.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_typesupport_fastrtps_cExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_typesupport_fastrtps_cppExport-none.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/export_unique_identifier_msgs__rosidl_typesupport_fastrtps_cppExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/rosidl_cmake-extras.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/rosidl_cmake_export_typesupport_libraries-extras.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/rosidl_cmake_export_typesupport_targets-extras.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgsConfig-version.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgsConfig.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgs__rosidl_typesupport_cExport-none.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgs__rosidl_typesupport_cExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgs__rosidl_typesupport_cppExport-none.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgs__rosidl_typesupport_cppExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgs__rosidl_typesupport_introspection_cExport-none.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgs__rosidl_typesupport_introspection_cExport.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgs__rosidl_typesupport_introspection_cppExport-none.cmake" + "/opt/ros/humble/share/unique_identifier_msgs/cmake/unique_identifier_msgs__rosidl_typesupport_introspection_cppExport.cmake" + "/usr/lib/x86_64-linux-gnu/cmake/fmt/fmt-config-version.cmake" + "/usr/lib/x86_64-linux-gnu/cmake/fmt/fmt-config.cmake" + "/usr/lib/x86_64-linux-gnu/cmake/fmt/fmt-targets-none.cmake" + "/usr/lib/x86_64-linux-gnu/cmake/fmt/fmt-targets.cmake" + "/usr/lib/x86_64-linux-gnu/cmake/spdlog/spdlogConfig.cmake" + "/usr/lib/x86_64-linux-gnu/cmake/spdlog/spdlogConfigTargets-none.cmake" + "/usr/lib/x86_64-linux-gnu/cmake/spdlog/spdlogConfigTargets.cmake" + "/usr/lib/x86_64-linux-gnu/cmake/spdlog/spdlogConfigVersion.cmake" + "/usr/share/cmake-3.22/Modules/CMakeCCompiler.cmake.in" + "/usr/share/cmake-3.22/Modules/CMakeCCompilerABI.c" + "/usr/share/cmake-3.22/Modules/CMakeCInformation.cmake" + "/usr/share/cmake-3.22/Modules/CMakeCXXCompiler.cmake.in" + "/usr/share/cmake-3.22/Modules/CMakeCXXCompilerABI.cpp" + "/usr/share/cmake-3.22/Modules/CMakeCXXInformation.cmake" + "/usr/share/cmake-3.22/Modules/CMakeCommonLanguageInclude.cmake" + "/usr/share/cmake-3.22/Modules/CMakeCompilerIdDetection.cmake" + "/usr/share/cmake-3.22/Modules/CMakeDetermineCCompiler.cmake" + "/usr/share/cmake-3.22/Modules/CMakeDetermineCXXCompiler.cmake" + "/usr/share/cmake-3.22/Modules/CMakeDetermineCompileFeatures.cmake" + "/usr/share/cmake-3.22/Modules/CMakeDetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/CMakeDetermineCompilerABI.cmake" + "/usr/share/cmake-3.22/Modules/CMakeDetermineCompilerId.cmake" + "/usr/share/cmake-3.22/Modules/CMakeDetermineSystem.cmake" + "/usr/share/cmake-3.22/Modules/CMakeFindBinUtils.cmake" + "/usr/share/cmake-3.22/Modules/CMakeFindDependencyMacro.cmake" + "/usr/share/cmake-3.22/Modules/CMakeGenericSystem.cmake" + "/usr/share/cmake-3.22/Modules/CMakeInitializeConfigs.cmake" + "/usr/share/cmake-3.22/Modules/CMakeLanguageInformation.cmake" + "/usr/share/cmake-3.22/Modules/CMakeParseImplicitIncludeInfo.cmake" + "/usr/share/cmake-3.22/Modules/CMakeParseImplicitLinkInfo.cmake" + "/usr/share/cmake-3.22/Modules/CMakeParseLibraryArchitecture.cmake" + "/usr/share/cmake-3.22/Modules/CMakeSystem.cmake.in" + "/usr/share/cmake-3.22/Modules/CMakeSystemSpecificInformation.cmake" + "/usr/share/cmake-3.22/Modules/CMakeSystemSpecificInitialize.cmake" + "/usr/share/cmake-3.22/Modules/CMakeTestCCompiler.cmake" + "/usr/share/cmake-3.22/Modules/CMakeTestCXXCompiler.cmake" + "/usr/share/cmake-3.22/Modules/CMakeTestCompilerCommon.cmake" + "/usr/share/cmake-3.22/Modules/CMakeUnixFindMake.cmake" + "/usr/share/cmake-3.22/Modules/CheckCSourceCompiles.cmake" + "/usr/share/cmake-3.22/Modules/CheckIncludeFile.c.in" + "/usr/share/cmake-3.22/Modules/CheckIncludeFile.cmake" + "/usr/share/cmake-3.22/Modules/CheckLibraryExists.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/ADSP-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/ARMCC-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/ARMClang-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/AppleClang-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Borland-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Bruce-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/CMakeCommonCompilerMacros.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Clang-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Clang-DetermineCompilerInternal.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Comeau-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Compaq-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Compaq-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Cray-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Embarcadero-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Fujitsu-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/FujitsuClang-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/GHS-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/GNU-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/GNU-C.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/GNU-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/GNU-CXX.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/GNU-FindBinUtils.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/GNU.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/HP-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/HP-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/IAR-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/IBMCPP-C-DetermineVersionInternal.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/IBMCPP-CXX-DetermineVersionInternal.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Intel-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/IntelLLVM-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/MSVC-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/NVHPC-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/NVIDIA-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/OpenWatcom-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/PGI-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/PathScale-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/SCO-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/SDCC-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/SunPro-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/SunPro-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/TI-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/TinyCC-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/VisualAge-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/VisualAge-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/Watcom-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/XL-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/XL-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/XLClang-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/XLClang-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/zOS-C-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/Compiler/zOS-CXX-DetermineCompiler.cmake" + "/usr/share/cmake-3.22/Modules/DartConfiguration.tcl.in" + "/usr/share/cmake-3.22/Modules/FindOpenSSL.cmake" + "/usr/share/cmake-3.22/Modules/FindPackageHandleStandardArgs.cmake" + "/usr/share/cmake-3.22/Modules/FindPackageMessage.cmake" + "/usr/share/cmake-3.22/Modules/FindPkgConfig.cmake" + "/usr/share/cmake-3.22/Modules/FindPython/Support.cmake" + "/usr/share/cmake-3.22/Modules/FindPython3.cmake" + "/usr/share/cmake-3.22/Modules/FindThreads.cmake" + "/usr/share/cmake-3.22/Modules/Internal/CheckSourceCompiles.cmake" + "/usr/share/cmake-3.22/Modules/Internal/FeatureTesting.cmake" + "/usr/share/cmake-3.22/Modules/Platform/Linux-Determine-CXX.cmake" + "/usr/share/cmake-3.22/Modules/Platform/Linux-GNU-C.cmake" + "/usr/share/cmake-3.22/Modules/Platform/Linux-GNU-CXX.cmake" + "/usr/share/cmake-3.22/Modules/Platform/Linux-GNU.cmake" + "/usr/share/cmake-3.22/Modules/Platform/Linux.cmake" + "/usr/share/cmake-3.22/Modules/Platform/UnixPaths.cmake" + "/usr/share/eigen3/cmake/Eigen3Config.cmake" + "/usr/share/eigen3/cmake/Eigen3ConfigVersion.cmake" + "/usr/share/eigen3/cmake/Eigen3Targets.cmake" + ) + +# The corresponding makefile is: +set(CMAKE_MAKEFILE_OUTPUTS + "Makefile" + "CMakeFiles/cmake.check_cache" + ) + +# Byproducts of CMake generate step: +set(CMAKE_MAKEFILE_PRODUCTS + "CMakeFiles/3.22.1/CMakeSystem.cmake" + "CMakeFiles/3.22.1/CMakeCCompiler.cmake" + "CMakeFiles/3.22.1/CMakeCXXCompiler.cmake" + "CMakeFiles/3.22.1/CMakeCCompiler.cmake" + "CMakeFiles/3.22.1/CMakeCXXCompiler.cmake" + "ament_cmake_core/stamps/templates_2_cmake.py.stamp" + "ament_cmake_uninstall_target/ament_cmake_uninstall_target.cmake" + "CTestConfiguration.ini" + "ament_cmake_core/stamps/package.xml.stamp" + "ament_cmake_core/stamps/package_xml_2_cmake.py.stamp" + "ament_cmake_core/stamps/ament_prefix_path.sh.stamp" + "ament_cmake_core/stamps/path.sh.stamp" + "ament_cmake_environment_hooks/local_setup.bash" + "ament_cmake_environment_hooks/local_setup.sh" + "ament_cmake_environment_hooks/local_setup.zsh" + "ament_cmake_core/stamps/nameConfig.cmake.in.stamp" + "ament_cmake_core/rm_arm_controlConfig.cmake" + "ament_cmake_core/stamps/nameConfig-version.cmake.in.stamp" + "ament_cmake_core/rm_arm_controlConfig-version.cmake" + "ament_cmake_index/share/ament_index/resource_index/package_run_dependencies/rm_arm_control" + "ament_cmake_index/share/ament_index/resource_index/parent_prefix_path/rm_arm_control" + "ament_cmake_index/share/ament_index/resource_index/packages/rm_arm_control" + "CMakeFiles/CMakeDirectoryInformation.cmake" + ) + +# Dependency information for all targets: +set(CMAKE_DEPEND_INFO_FILES + "CMakeFiles/uninstall.dir/DependInfo.cmake" + "CMakeFiles/rm_arm_control_uninstall.dir/DependInfo.cmake" + "CMakeFiles/rm_arm_control.dir/DependInfo.cmake" + ) diff --git a/rm_arm_control/build/CMakeFiles/Makefile2 b/rm_arm_control/build/CMakeFiles/Makefile2 new file mode 100644 index 0000000..8f2d4aa --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/Makefile2 @@ -0,0 +1,166 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 3.22 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Disable VCS-based implicit rules. +% : %,v + +# Disable VCS-based implicit rules. +% : RCS/% + +# Disable VCS-based implicit rules. +% : RCS/%,v + +# Disable VCS-based implicit rules. +% : SCCS/s.% + +# Disable VCS-based implicit rules. +% : s.% + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Command-line flag to silence nested $(MAKE). +$(VERBOSE)MAKESILENT = -s + +#Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E rm -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build + +#============================================================================= +# Directory level rules for the build root directory + +# The main recursive "all" target. +all: CMakeFiles/rm_arm_control.dir/all +.PHONY : all + +# The main recursive "preinstall" target. +preinstall: +.PHONY : preinstall + +# The main recursive "clean" target. +clean: CMakeFiles/uninstall.dir/clean +clean: CMakeFiles/rm_arm_control_uninstall.dir/clean +clean: CMakeFiles/rm_arm_control.dir/clean +.PHONY : clean + +#============================================================================= +# Target rules for target CMakeFiles/uninstall.dir + +# All Build rule for target. +CMakeFiles/uninstall.dir/all: CMakeFiles/rm_arm_control_uninstall.dir/all + $(MAKE) $(MAKESILENT) -f CMakeFiles/uninstall.dir/build.make CMakeFiles/uninstall.dir/depend + $(MAKE) $(MAKESILENT) -f CMakeFiles/uninstall.dir/build.make CMakeFiles/uninstall.dir/build + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles --progress-num= "Built target uninstall" +.PHONY : CMakeFiles/uninstall.dir/all + +# Build rule for subdir invocation for target. +CMakeFiles/uninstall.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles 0 + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 CMakeFiles/uninstall.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles 0 +.PHONY : CMakeFiles/uninstall.dir/rule + +# Convenience name for target. +uninstall: CMakeFiles/uninstall.dir/rule +.PHONY : uninstall + +# clean rule for target. +CMakeFiles/uninstall.dir/clean: + $(MAKE) $(MAKESILENT) -f CMakeFiles/uninstall.dir/build.make CMakeFiles/uninstall.dir/clean +.PHONY : CMakeFiles/uninstall.dir/clean + +#============================================================================= +# Target rules for target CMakeFiles/rm_arm_control_uninstall.dir + +# All Build rule for target. +CMakeFiles/rm_arm_control_uninstall.dir/all: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control_uninstall.dir/build.make CMakeFiles/rm_arm_control_uninstall.dir/depend + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control_uninstall.dir/build.make CMakeFiles/rm_arm_control_uninstall.dir/build + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles --progress-num= "Built target rm_arm_control_uninstall" +.PHONY : CMakeFiles/rm_arm_control_uninstall.dir/all + +# Build rule for subdir invocation for target. +CMakeFiles/rm_arm_control_uninstall.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles 0 + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 CMakeFiles/rm_arm_control_uninstall.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles 0 +.PHONY : CMakeFiles/rm_arm_control_uninstall.dir/rule + +# Convenience name for target. +rm_arm_control_uninstall: CMakeFiles/rm_arm_control_uninstall.dir/rule +.PHONY : rm_arm_control_uninstall + +# clean rule for target. +CMakeFiles/rm_arm_control_uninstall.dir/clean: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control_uninstall.dir/build.make CMakeFiles/rm_arm_control_uninstall.dir/clean +.PHONY : CMakeFiles/rm_arm_control_uninstall.dir/clean + +#============================================================================= +# Target rules for target CMakeFiles/rm_arm_control.dir + +# All Build rule for target. +CMakeFiles/rm_arm_control.dir/all: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/depend + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/build + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --progress-dir=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles --progress-num=1,2,3 "Built target rm_arm_control" +.PHONY : CMakeFiles/rm_arm_control.dir/all + +# Build rule for subdir invocation for target. +CMakeFiles/rm_arm_control.dir/rule: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles 3 + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 CMakeFiles/rm_arm_control.dir/all + $(CMAKE_COMMAND) -E cmake_progress_start /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles 0 +.PHONY : CMakeFiles/rm_arm_control.dir/rule + +# Convenience name for target. +rm_arm_control: CMakeFiles/rm_arm_control.dir/rule +.PHONY : rm_arm_control + +# clean rule for target. +CMakeFiles/rm_arm_control.dir/clean: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/clean +.PHONY : CMakeFiles/rm_arm_control.dir/clean + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/rm_arm_control/build/CMakeFiles/TargetDirectories.txt b/rm_arm_control/build/CMakeFiles/TargetDirectories.txt new file mode 100644 index 0000000..02ab3ae --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/TargetDirectories.txt @@ -0,0 +1,10 @@ +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/uninstall.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/rm_arm_control.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/test.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/edit_cache.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/rebuild_cache.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/list_install_components.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/install.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/install/local.dir +/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/install/strip.dir diff --git a/rm_arm_control/build/CMakeFiles/cmake.check_cache b/rm_arm_control/build/CMakeFiles/cmake.check_cache new file mode 100644 index 0000000..3dccd73 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/cmake.check_cache @@ -0,0 +1 @@ +# This file is generated by cmake for dependency checking of the CMakeCache.txt file diff --git a/rm_arm_control/build/CMakeFiles/progress.marks b/rm_arm_control/build/CMakeFiles/progress.marks new file mode 100644 index 0000000..00750ed --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/progress.marks @@ -0,0 +1 @@ +3 diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/DependInfo.cmake b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/DependInfo.cmake new file mode 100644 index 0000000..c4b91c9 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/DependInfo.cmake @@ -0,0 +1,20 @@ + +# Consider dependencies only in project. +set(CMAKE_DEPENDS_IN_PROJECT_ONLY OFF) + +# The set of languages for which implicit dependencies are needed: +set(CMAKE_DEPENDS_LANGUAGES + ) + +# The set of dependency files which are needed: +set(CMAKE_DEPENDS_DEPENDENCY_FILES + "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_handler.cpp" "CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o" "gcc" "CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o.d" + "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_node.cpp" "CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o" "gcc" "CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o.d" + ) + +# Targets to which this target links. +set(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# Fortran module output directory. +set(CMAKE_Fortran_TARGET_MODULE_DIR "") diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/build.make b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/build.make new file mode 100644 index 0000000..38d21e0 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/build.make @@ -0,0 +1,238 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 3.22 + +# Delete rule output on recipe failure. +.DELETE_ON_ERROR: + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Disable VCS-based implicit rules. +% : %,v + +# Disable VCS-based implicit rules. +% : RCS/% + +# Disable VCS-based implicit rules. +% : RCS/%,v + +# Disable VCS-based implicit rules. +% : SCCS/s.% + +# Disable VCS-based implicit rules. +% : s.% + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Command-line flag to silence nested $(MAKE). +$(VERBOSE)MAKESILENT = -s + +#Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E rm -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build + +# Include any dependencies generated for this target. +include CMakeFiles/rm_arm_control.dir/depend.make +# Include any dependencies generated by the compiler for this target. +include CMakeFiles/rm_arm_control.dir/compiler_depend.make + +# Include the progress variables for this target. +include CMakeFiles/rm_arm_control.dir/progress.make + +# Include the compile flags for this target's objects. +include CMakeFiles/rm_arm_control.dir/flags.make + +CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o: CMakeFiles/rm_arm_control.dir/flags.make +CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o: ../src/rm_arm_handler.cpp +CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o: CMakeFiles/rm_arm_control.dir/compiler_depend.ts + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles --progress-num=$(CMAKE_PROGRESS_1) "Building CXX object CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -MD -MT CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o -MF CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o.d -o CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o -c /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_handler.cpp + +CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.i" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_handler.cpp > CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.i + +CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.s" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_handler.cpp -o CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.s + +CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o: CMakeFiles/rm_arm_control.dir/flags.make +CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o: ../src/rm_arm_node.cpp +CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o: CMakeFiles/rm_arm_control.dir/compiler_depend.ts + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles --progress-num=$(CMAKE_PROGRESS_2) "Building CXX object CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -MD -MT CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o -MF CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o.d -o CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o -c /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_node.cpp + +CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.i: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing CXX source to CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.i" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -E /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_node.cpp > CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.i + +CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.s: cmake_force + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling CXX source to assembly CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.s" + /usr/bin/c++ $(CXX_DEFINES) $(CXX_INCLUDES) $(CXX_FLAGS) -S /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_node.cpp -o CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.s + +# Object files for target rm_arm_control +rm_arm_control_OBJECTS = \ +"CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o" \ +"CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o" + +# External object files for target rm_arm_control +rm_arm_control_EXTERNAL_OBJECTS = + +rm_arm_control: CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o +rm_arm_control: CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o +rm_arm_control: CMakeFiles/rm_arm_control.dir/build.make +rm_arm_control: /opt/ros/humble/lib/librclcpp.so +rm_arm_control: /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libcontrol_msgs__rosidl_generator_py.so +rm_arm_control: /home/zj/hivecore_robot_os/HiveCoreR1/lib/libapi_cpp.so +rm_arm_control: /opt/ros/humble/lib/liblibstatistics_collector.so +rm_arm_control: /opt/ros/humble/lib/librcl.so +rm_arm_control: /opt/ros/humble/lib/librmw_implementation.so +rm_arm_control: /opt/ros/humble/lib/libament_index_cpp.so +rm_arm_control: /opt/ros/humble/lib/librcl_logging_spdlog.so +rm_arm_control: /opt/ros/humble/lib/librcl_logging_interface.so +rm_arm_control: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/librcl_interfaces__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/librcl_interfaces__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/librcl_yaml_param_parser.so +rm_arm_control: /opt/ros/humble/lib/libyaml.so +rm_arm_control: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/librosgraph_msgs__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/librosgraph_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libstatistics_msgs__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libstatistics_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libtracetools.so +rm_arm_control: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/librosidl_typesupport_fastrtps_c.so +rm_arm_control: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/librosidl_typesupport_fastrtps_cpp.so +rm_arm_control: /opt/ros/humble/lib/libfastcdr.so.1.0.24 +rm_arm_control: /opt/ros/humble/lib/librmw.so +rm_arm_control: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/librosidl_typesupport_introspection_cpp.so +rm_arm_control: /opt/ros/humble/lib/librosidl_typesupport_introspection_c.so +rm_arm_control: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/librosidl_typesupport_cpp.so +rm_arm_control: /opt/ros/humble/lib/libsensor_msgs__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/libtrajectory_msgs__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/libgeometry_msgs__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libcontrol_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libsensor_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libtrajectory_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libgeometry_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libstd_msgs__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libstd_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libaction_msgs__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_generator_py.so +rm_arm_control: /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libaction_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_generator_py.so +rm_arm_control: /usr/lib/x86_64-linux-gnu/libpython3.10.so +rm_arm_control: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_generator_c.so +rm_arm_control: /opt/ros/humble/lib/librosidl_typesupport_c.so +rm_arm_control: /opt/ros/humble/lib/librcpputils.so +rm_arm_control: /opt/ros/humble/lib/librosidl_runtime_c.so +rm_arm_control: /opt/ros/humble/lib/librcutils.so +rm_arm_control: CMakeFiles/rm_arm_control.dir/link.txt + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles --progress-num=$(CMAKE_PROGRESS_3) "Linking CXX executable rm_arm_control" + $(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/rm_arm_control.dir/link.txt --verbose=$(VERBOSE) + /usr/bin/cmake -E copy_if_different /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../lib/libapi_cpp.so /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build + +# Rule to build all files generated by this target. +CMakeFiles/rm_arm_control.dir/build: rm_arm_control +.PHONY : CMakeFiles/rm_arm_control.dir/build + +CMakeFiles/rm_arm_control.dir/clean: + $(CMAKE_COMMAND) -P CMakeFiles/rm_arm_control.dir/cmake_clean.cmake +.PHONY : CMakeFiles/rm_arm_control.dir/clean + +CMakeFiles/rm_arm_control.dir/depend: + cd /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/DependInfo.cmake --color=$(COLOR) +.PHONY : CMakeFiles/rm_arm_control.dir/depend + diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/cmake_clean.cmake b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/cmake_clean.cmake new file mode 100644 index 0000000..c9d9a57 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/cmake_clean.cmake @@ -0,0 +1,13 @@ +file(REMOVE_RECURSE + "CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o" + "CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o.d" + "CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o" + "CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o.d" + "rm_arm_control" + "rm_arm_control.pdb" +) + +# Per-language clean rules from dependency scanning. +foreach(lang CXX) + include(CMakeFiles/rm_arm_control.dir/cmake_clean_${lang}.cmake OPTIONAL) +endforeach() diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/compiler_depend.make b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/compiler_depend.make new file mode 100644 index 0000000..2d787e7 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/compiler_depend.make @@ -0,0 +1,2 @@ +# Empty compiler generated dependencies file for rm_arm_control. +# This may be replaced when dependencies are built. diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/compiler_depend.ts b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/compiler_depend.ts new file mode 100644 index 0000000..a3286d8 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/compiler_depend.ts @@ -0,0 +1,2 @@ +# CMAKE generated file: DO NOT EDIT! +# Timestamp file for compiler generated dependencies management for rm_arm_control. diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/depend.make b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/depend.make new file mode 100644 index 0000000..42bdff6 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/depend.make @@ -0,0 +1,2 @@ +# Empty dependencies file for rm_arm_control. +# This may be replaced when dependencies are built. diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/flags.make b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/flags.make new file mode 100644 index 0000000..f93ae4c --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/flags.make @@ -0,0 +1,10 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 3.22 + +# compile CXX with /usr/bin/c++ +CXX_DEFINES = -DDEFAULT_RMW_IMPLEMENTATION=rmw_fastrtps_cpp -DRCUTILS_ENABLE_FAULT_INJECTION + +CXX_INCLUDES = -I/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/include -I/usr/include/eigen3 -I/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include -isystem /opt/ros/humble/include/rclcpp -isystem /opt/ros/humble/include/geometry_msgs -isystem /opt/ros/humble/include/sensor_msgs -isystem /opt/ros/humble/include/trajectory_msgs -isystem /opt/ros/humble/include/control_msgs -isystem /opt/ros/humble/include/ament_index_cpp -isystem /opt/ros/humble/include/libstatistics_collector -isystem /opt/ros/humble/include/builtin_interfaces -isystem /opt/ros/humble/include/rosidl_runtime_c -isystem /opt/ros/humble/include/rcutils -isystem /opt/ros/humble/include/rosidl_typesupport_interface -isystem /opt/ros/humble/include/fastcdr -isystem /opt/ros/humble/include/rosidl_runtime_cpp -isystem /opt/ros/humble/include/rosidl_typesupport_fastrtps_cpp -isystem /opt/ros/humble/include/rmw -isystem /opt/ros/humble/include/rosidl_typesupport_fastrtps_c -isystem /opt/ros/humble/include/rosidl_typesupport_introspection_c -isystem /opt/ros/humble/include/rosidl_typesupport_introspection_cpp -isystem /opt/ros/humble/include/rcl -isystem /opt/ros/humble/include/rcl_interfaces -isystem /opt/ros/humble/include/rcl_logging_interface -isystem /opt/ros/humble/include/rcl_yaml_param_parser -isystem /opt/ros/humble/include/libyaml_vendor -isystem /opt/ros/humble/include/tracetools -isystem /opt/ros/humble/include/rcpputils -isystem /opt/ros/humble/include/statistics_msgs -isystem /opt/ros/humble/include/rosgraph_msgs -isystem /opt/ros/humble/include/rosidl_typesupport_cpp -isystem /opt/ros/humble/include/rosidl_typesupport_c -isystem /opt/ros/humble/include/std_msgs -isystem /opt/ros/humble/include/action_msgs -isystem /opt/ros/humble/include/unique_identifier_msgs + +CXX_FLAGS = -Wno-define-redefinition -g + diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/link.txt b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/link.txt new file mode 100644 index 0000000..c0862b8 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/link.txt @@ -0,0 +1 @@ +/usr/bin/c++ CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o -o rm_arm_control -Wl,-rpath,/opt/ros/humble/lib:/home/zj/hivecore_robot_os/HiveCoreR1/lib: /opt/ros/humble/lib/librclcpp.so /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/libcontrol_msgs__rosidl_generator_py.so /home/zj/hivecore_robot_os/HiveCoreR1/lib/libapi_cpp.so /opt/ros/humble/lib/liblibstatistics_collector.so /opt/ros/humble/lib/librcl.so /opt/ros/humble/lib/librmw_implementation.so /opt/ros/humble/lib/libament_index_cpp.so /opt/ros/humble/lib/librcl_logging_spdlog.so /opt/ros/humble/lib/librcl_logging_interface.so /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_cpp.so /opt/ros/humble/lib/librcl_interfaces__rosidl_generator_py.so /opt/ros/humble/lib/librcl_interfaces__rosidl_typesupport_c.so /opt/ros/humble/lib/librcl_interfaces__rosidl_generator_c.so /opt/ros/humble/lib/librcl_yaml_param_parser.so /opt/ros/humble/lib/libyaml.so /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/librosgraph_msgs__rosidl_generator_py.so /opt/ros/humble/lib/librosgraph_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/librosgraph_msgs__rosidl_generator_c.so /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/libstatistics_msgs__rosidl_generator_py.so /opt/ros/humble/lib/libstatistics_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/libstatistics_msgs__rosidl_generator_c.so /opt/ros/humble/lib/libtracetools.so /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/librosidl_typesupport_fastrtps_c.so /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/librosidl_typesupport_fastrtps_cpp.so /opt/ros/humble/lib/libfastcdr.so.1.0.24 /opt/ros/humble/lib/librmw.so /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/librosidl_typesupport_introspection_cpp.so /opt/ros/humble/lib/librosidl_typesupport_introspection_c.so /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_cpp.so /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_cpp.so /opt/ros/humble/lib/librosidl_typesupport_cpp.so /opt/ros/humble/lib/libsensor_msgs__rosidl_generator_py.so /opt/ros/humble/lib/libtrajectory_msgs__rosidl_generator_py.so /opt/ros/humble/lib/libgeometry_msgs__rosidl_generator_py.so /opt/ros/humble/lib/libcontrol_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/libsensor_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/libtrajectory_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/libgeometry_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/libcontrol_msgs__rosidl_generator_c.so /opt/ros/humble/lib/libsensor_msgs__rosidl_generator_c.so /opt/ros/humble/lib/libtrajectory_msgs__rosidl_generator_c.so /opt/ros/humble/lib/libgeometry_msgs__rosidl_generator_c.so /opt/ros/humble/lib/libstd_msgs__rosidl_generator_py.so /opt/ros/humble/lib/libstd_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/libstd_msgs__rosidl_generator_c.so /opt/ros/humble/lib/libaction_msgs__rosidl_generator_py.so /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_generator_py.so /opt/ros/humble/lib/libaction_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_typesupport_c.so /opt/ros/humble/lib/libaction_msgs__rosidl_generator_c.so /opt/ros/humble/lib/libbuiltin_interfaces__rosidl_generator_c.so /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_generator_py.so /usr/lib/x86_64-linux-gnu/libpython3.10.so /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_typesupport_c.so /opt/ros/humble/lib/libunique_identifier_msgs__rosidl_generator_c.so /opt/ros/humble/lib/librosidl_typesupport_c.so /opt/ros/humble/lib/librcpputils.so /opt/ros/humble/lib/librosidl_runtime_c.so /opt/ros/humble/lib/librcutils.so -ldl diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/progress.make b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/progress.make new file mode 100644 index 0000000..6a9dc74 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/progress.make @@ -0,0 +1,4 @@ +CMAKE_PROGRESS_1 = 1 +CMAKE_PROGRESS_2 = 2 +CMAKE_PROGRESS_3 = 3 + diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o new file mode 100644 index 0000000..dd2564a Binary files /dev/null and b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o differ diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o.d b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o.d new file mode 100644 index 0000000..052fff3 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o.d @@ -0,0 +1,662 @@ +CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o: \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_handler.cpp \ + /usr/include/stdc-predef.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/include/rm_arm_handler.hpp \ + /usr/include/c++/11/cstdlib \ + /usr/include/x86_64-linux-gnu/c++/11/bits/c++config.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/os_defines.h \ + /usr/include/features.h /usr/include/features-time64.h \ + /usr/include/x86_64-linux-gnu/bits/wordsize.h \ + /usr/include/x86_64-linux-gnu/bits/timesize.h \ + /usr/include/x86_64-linux-gnu/sys/cdefs.h \ + /usr/include/x86_64-linux-gnu/bits/long-double.h \ + /usr/include/x86_64-linux-gnu/gnu/stubs.h \ + /usr/include/x86_64-linux-gnu/gnu/stubs-64.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/cpu_defines.h \ + /usr/include/c++/11/pstl/pstl_config.h /usr/include/stdlib.h \ + /usr/include/x86_64-linux-gnu/bits/libc-header-start.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stddef.h \ + /usr/include/x86_64-linux-gnu/bits/waitflags.h \ + /usr/include/x86_64-linux-gnu/bits/waitstatus.h \ + /usr/include/x86_64-linux-gnu/bits/floatn.h \ + /usr/include/x86_64-linux-gnu/bits/floatn-common.h \ + /usr/include/x86_64-linux-gnu/bits/types/locale_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__locale_t.h \ + /usr/include/x86_64-linux-gnu/sys/types.h \ + /usr/include/x86_64-linux-gnu/bits/types.h \ + /usr/include/x86_64-linux-gnu/bits/typesizes.h \ + /usr/include/x86_64-linux-gnu/bits/time64.h \ + /usr/include/x86_64-linux-gnu/bits/types/clock_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/clockid_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/time_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/timer_t.h \ + /usr/include/x86_64-linux-gnu/bits/stdint-intn.h /usr/include/endian.h \ + /usr/include/x86_64-linux-gnu/bits/endian.h \ + /usr/include/x86_64-linux-gnu/bits/endianness.h \ + /usr/include/x86_64-linux-gnu/bits/byteswap.h \ + /usr/include/x86_64-linux-gnu/bits/uintn-identity.h \ + /usr/include/x86_64-linux-gnu/sys/select.h \ + /usr/include/x86_64-linux-gnu/bits/select.h \ + /usr/include/x86_64-linux-gnu/bits/types/sigset_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__sigset_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_timeval.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_timespec.h \ + /usr/include/x86_64-linux-gnu/bits/pthreadtypes.h \ + /usr/include/x86_64-linux-gnu/bits/thread-shared-types.h \ + /usr/include/x86_64-linux-gnu/bits/pthreadtypes-arch.h \ + /usr/include/x86_64-linux-gnu/bits/atomic_wide_counter.h \ + /usr/include/x86_64-linux-gnu/bits/struct_mutex.h \ + /usr/include/x86_64-linux-gnu/bits/struct_rwlock.h /usr/include/alloca.h \ + /usr/include/x86_64-linux-gnu/bits/stdlib-float.h \ + /usr/include/c++/11/bits/std_abs.h /usr/include/stdio.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stdarg.h \ + /usr/include/x86_64-linux-gnu/bits/types/__fpos_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__mbstate_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__fpos64_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__FILE.h \ + /usr/include/x86_64-linux-gnu/bits/types/FILE.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_FILE.h \ + /usr/include/x86_64-linux-gnu/bits/types/cookie_io_functions_t.h \ + /usr/include/x86_64-linux-gnu/bits/stdio_lim.h /usr/include/unistd.h \ + /usr/include/x86_64-linux-gnu/bits/posix_opt.h \ + /usr/include/x86_64-linux-gnu/bits/environments.h \ + /usr/include/x86_64-linux-gnu/bits/confname.h \ + /usr/include/x86_64-linux-gnu/bits/getopt_posix.h \ + /usr/include/x86_64-linux-gnu/bits/getopt_core.h \ + /usr/include/x86_64-linux-gnu/bits/unistd_ext.h \ + /usr/include/linux/close_range.h \ + /usr/include/x86_64-linux-gnu/sys/stat.h \ + /usr/include/x86_64-linux-gnu/bits/stat.h \ + /usr/include/x86_64-linux-gnu/bits/struct_stat.h \ + /usr/include/x86_64-linux-gnu/bits/statx.h /usr/include/linux/stat.h \ + /usr/include/linux/types.h /usr/include/x86_64-linux-gnu/asm/types.h \ + /usr/include/asm-generic/types.h /usr/include/asm-generic/int-ll64.h \ + /usr/include/x86_64-linux-gnu/asm/bitsperlong.h \ + /usr/include/asm-generic/bitsperlong.h /usr/include/linux/posix_types.h \ + /usr/include/linux/stddef.h \ + /usr/include/x86_64-linux-gnu/asm/posix_types.h \ + /usr/include/x86_64-linux-gnu/asm/posix_types_64.h \ + /usr/include/asm-generic/posix_types.h \ + /usr/include/x86_64-linux-gnu/bits/statx-generic.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_statx_timestamp.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_statx.h \ + /usr/include/x86_64-linux-gnu/sys/time.h \ + /opt/ros/humble/include/rclcpp/rclcpp/rclcpp.hpp \ + /usr/include/c++/11/csignal /usr/include/signal.h \ + /usr/include/x86_64-linux-gnu/bits/signum-generic.h \ + /usr/include/x86_64-linux-gnu/bits/signum-arch.h \ + /usr/include/x86_64-linux-gnu/bits/types/sig_atomic_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/siginfo_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__sigval_t.h \ + /usr/include/x86_64-linux-gnu/bits/siginfo-arch.h \ + /usr/include/x86_64-linux-gnu/bits/siginfo-consts.h \ + /usr/include/x86_64-linux-gnu/bits/siginfo-consts-arch.h \ + /usr/include/x86_64-linux-gnu/bits/types/sigval_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/sigevent_t.h \ + /usr/include/x86_64-linux-gnu/bits/sigevent-consts.h \ + /usr/include/x86_64-linux-gnu/bits/sigaction.h \ + /usr/include/x86_64-linux-gnu/bits/sigcontext.h \ + /usr/include/x86_64-linux-gnu/bits/types/stack_t.h \ + /usr/include/x86_64-linux-gnu/sys/ucontext.h \ + /usr/include/x86_64-linux-gnu/bits/sigstack.h \ + /usr/include/x86_64-linux-gnu/bits/sigstksz.h \ + /usr/include/x86_64-linux-gnu/bits/ss_flags.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_sigstack.h \ + /usr/include/x86_64-linux-gnu/bits/sigthread.h \ + /usr/include/x86_64-linux-gnu/bits/signal_ext.h \ + /usr/include/c++/11/memory /usr/include/c++/11/bits/stl_algobase.h \ + /usr/include/c++/11/bits/functexcept.h \ + /usr/include/c++/11/bits/exception_defines.h \ + /usr/include/c++/11/bits/cpp_type_traits.h \ + /usr/include/c++/11/ext/type_traits.h \ + /usr/include/c++/11/ext/numeric_traits.h \ + /usr/include/c++/11/bits/stl_pair.h /usr/include/c++/11/bits/move.h \ + /usr/include/c++/11/type_traits \ + /usr/include/c++/11/bits/stl_iterator_base_types.h \ + /usr/include/c++/11/bits/stl_iterator_base_funcs.h \ + /usr/include/c++/11/bits/concept_check.h \ + /usr/include/c++/11/debug/assertions.h \ + /usr/include/c++/11/bits/stl_iterator.h \ + /usr/include/c++/11/bits/ptr_traits.h /usr/include/c++/11/debug/debug.h \ + /usr/include/c++/11/bits/predefined_ops.h \ + /usr/include/c++/11/bits/allocator.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/c++allocator.h \ + /usr/include/c++/11/ext/new_allocator.h /usr/include/c++/11/new \ + /usr/include/c++/11/bits/exception.h \ + /usr/include/c++/11/bits/memoryfwd.h \ + /usr/include/c++/11/bits/stl_construct.h \ + /usr/include/c++/11/bits/stl_uninitialized.h \ + /usr/include/c++/11/ext/alloc_traits.h \ + /usr/include/c++/11/bits/alloc_traits.h \ + /usr/include/c++/11/bits/stl_tempbuf.h \ + /usr/include/c++/11/bits/stl_raw_storage_iter.h \ + /usr/include/c++/11/bits/align.h /usr/include/c++/11/bit \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stdint.h /usr/include/stdint.h \ + /usr/include/x86_64-linux-gnu/bits/wchar.h \ + /usr/include/x86_64-linux-gnu/bits/stdint-uintn.h \ + /usr/include/c++/11/bits/uses_allocator.h \ + /usr/include/c++/11/bits/unique_ptr.h /usr/include/c++/11/utility \ + /usr/include/c++/11/bits/stl_relops.h \ + /usr/include/c++/11/initializer_list /usr/include/c++/11/tuple \ + /usr/include/c++/11/array /usr/include/c++/11/bits/range_access.h \ + /usr/include/c++/11/bits/invoke.h \ + /usr/include/c++/11/bits/stl_function.h \ + /usr/include/c++/11/backward/binders.h \ + /usr/include/c++/11/bits/functional_hash.h \ + /usr/include/c++/11/bits/hash_bytes.h \ + /usr/include/c++/11/bits/shared_ptr.h /usr/include/c++/11/iosfwd \ + /usr/include/c++/11/bits/stringfwd.h /usr/include/c++/11/bits/postypes.h \ + /usr/include/c++/11/cwchar /usr/include/wchar.h \ + /usr/include/x86_64-linux-gnu/bits/types/wint_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/mbstate_t.h \ + /usr/include/c++/11/bits/shared_ptr_base.h /usr/include/c++/11/typeinfo \ + /usr/include/c++/11/bits/allocated_ptr.h \ + /usr/include/c++/11/bits/refwrap.h \ + /usr/include/c++/11/ext/aligned_buffer.h \ + /usr/include/c++/11/ext/atomicity.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/gthr.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h \ + /usr/include/pthread.h /usr/include/sched.h \ + /usr/include/x86_64-linux-gnu/bits/sched.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_sched_param.h \ + /usr/include/x86_64-linux-gnu/bits/cpu-set.h /usr/include/time.h \ + /usr/include/x86_64-linux-gnu/bits/time.h \ + /usr/include/x86_64-linux-gnu/bits/timex.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_tm.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_itimerspec.h \ + /usr/include/x86_64-linux-gnu/bits/setjmp.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct___jmp_buf_tag.h \ + /usr/include/x86_64-linux-gnu/bits/pthread_stack_min-dynamic.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/atomic_word.h \ + /usr/include/x86_64-linux-gnu/sys/single_threaded.h \ + /usr/include/c++/11/ext/concurrence.h /usr/include/c++/11/exception \ + /usr/include/c++/11/bits/exception_ptr.h \ + /usr/include/c++/11/bits/cxxabi_init_exception.h \ + /usr/include/c++/11/bits/nested_exception.h \ + /usr/include/c++/11/bits/shared_ptr_atomic.h \ + /usr/include/c++/11/bits/atomic_base.h \ + /usr/include/c++/11/bits/atomic_lockfree_defines.h \ + /usr/include/c++/11/backward/auto_ptr.h \ + /usr/include/c++/11/pstl/glue_memory_defs.h \ + /usr/include/c++/11/pstl/execution_defs.h \ + /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp \ + /usr/include/c++/11/future /usr/include/c++/11/mutex \ + /usr/include/c++/11/chrono /usr/include/c++/11/ratio \ + /usr/include/c++/11/cstdint /usr/include/c++/11/limits \ + /usr/include/c++/11/ctime /usr/include/c++/11/bits/parse_numbers.h \ + /usr/include/c++/11/system_error \ + /usr/include/x86_64-linux-gnu/c++/11/bits/error_constants.h \ + /usr/include/c++/11/cerrno /usr/include/errno.h \ + /usr/include/x86_64-linux-gnu/bits/errno.h /usr/include/linux/errno.h \ + /usr/include/x86_64-linux-gnu/asm/errno.h \ + /usr/include/asm-generic/errno.h /usr/include/asm-generic/errno-base.h \ + /usr/include/x86_64-linux-gnu/bits/types/error_t.h \ + /usr/include/c++/11/stdexcept /usr/include/c++/11/string \ + /usr/include/c++/11/bits/char_traits.h \ + /usr/include/c++/11/bits/localefwd.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/c++locale.h \ + /usr/include/c++/11/clocale /usr/include/locale.h \ + /usr/include/x86_64-linux-gnu/bits/locale.h /usr/include/c++/11/cctype \ + /usr/include/ctype.h /usr/include/c++/11/bits/ostream_insert.h \ + /usr/include/c++/11/bits/cxxabi_forced.h \ + /usr/include/c++/11/bits/basic_string.h /usr/include/c++/11/string_view \ + /usr/include/c++/11/bits/string_view.tcc \ + /usr/include/c++/11/ext/string_conversions.h /usr/include/c++/11/cstdio \ + /usr/include/c++/11/bits/charconv.h \ + /usr/include/c++/11/bits/basic_string.tcc \ + /usr/include/c++/11/bits/std_mutex.h \ + /usr/include/c++/11/bits/unique_lock.h \ + /usr/include/c++/11/condition_variable /usr/include/c++/11/atomic \ + /usr/include/c++/11/bits/atomic_futex.h \ + /usr/include/c++/11/bits/std_function.h \ + /usr/include/c++/11/bits/std_thread.h \ + /opt/ros/humble/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp \ + /usr/include/c++/11/set /usr/include/c++/11/bits/stl_tree.h \ + /usr/include/c++/11/bits/node_handle.h \ + /usr/include/c++/11/bits/stl_set.h \ + /usr/include/c++/11/bits/stl_multiset.h \ + /usr/include/c++/11/bits/erase_if.h /usr/include/c++/11/thread \ + /usr/include/c++/11/bits/this_thread_sleep.h \ + /usr/include/c++/11/unordered_map /usr/include/c++/11/bits/hashtable.h \ + /usr/include/c++/11/bits/hashtable_policy.h \ + /usr/include/c++/11/bits/enable_special_members.h \ + /usr/include/c++/11/bits/unordered_map.h \ + /opt/ros/humble/include/rclcpp/rclcpp/executor.hpp \ + /usr/include/c++/11/algorithm /usr/include/c++/11/bits/stl_algo.h \ + /usr/include/c++/11/bits/algorithmfwd.h \ + /usr/include/c++/11/bits/stl_heap.h \ + /usr/include/c++/11/bits/uniform_int_dist.h \ + /usr/include/c++/11/pstl/glue_algorithm_defs.h \ + /usr/include/c++/11/functional /usr/include/c++/11/vector \ + /usr/include/c++/11/bits/stl_vector.h \ + /usr/include/c++/11/bits/stl_bvector.h \ + /usr/include/c++/11/bits/vector.tcc /usr/include/c++/11/cassert \ + /usr/include/assert.h /usr/include/c++/11/iostream \ + /usr/include/c++/11/ostream /usr/include/c++/11/ios \ + /usr/include/c++/11/bits/ios_base.h \ + /usr/include/c++/11/bits/locale_classes.h \ + /usr/include/c++/11/bits/locale_classes.tcc \ + /usr/include/c++/11/streambuf /usr/include/c++/11/bits/streambuf.tcc \ + /usr/include/c++/11/bits/basic_ios.h \ + /usr/include/c++/11/bits/locale_facets.h /usr/include/c++/11/cwctype \ + /usr/include/wctype.h /usr/include/x86_64-linux-gnu/bits/wctype-wchar.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/ctype_base.h \ + /usr/include/c++/11/bits/streambuf_iterator.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/ctype_inline.h \ + /usr/include/c++/11/bits/locale_facets.tcc \ + /usr/include/c++/11/bits/basic_ios.tcc \ + /usr/include/c++/11/bits/ostream.tcc /usr/include/c++/11/istream \ + /usr/include/c++/11/bits/istream.tcc /usr/include/c++/11/list \ + /usr/include/c++/11/bits/stl_list.h /usr/include/c++/11/bits/list.tcc \ + /usr/include/c++/11/map /usr/include/c++/11/bits/stl_map.h \ + /usr/include/c++/11/bits/stl_multimap.h \ + /opt/ros/humble/include/rcl/rcl/guard_condition.h \ + /opt/ros/humble/include/rcl/rcl/allocator.h \ + /opt/ros/humble/include/rcutils/rcutils/allocator.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stdbool.h \ + /opt/ros/humble/include/rcutils/rcutils/macros.h \ + /opt/ros/humble/include/rcutils/rcutils/testing/fault_injection.h \ + /opt/ros/humble/include/rcutils/rcutils/visibility_control.h \ + /opt/ros/humble/include/rcutils/rcutils/visibility_control_macros.h \ + /opt/ros/humble/include/rcutils/rcutils/types/rcutils_ret.h \ + /opt/ros/humble/include/rcl/rcl/context.h \ + /opt/ros/humble/include/rmw/rmw/init.h \ + /opt/ros/humble/include/rmw/rmw/init_options.h \ + /opt/ros/humble/include/rmw/rmw/domain_id.h \ + /opt/ros/humble/include/rmw/rmw/localhost.h \ + /opt/ros/humble/include/rmw/rmw/visibility_control.h \ + /opt/ros/humble/include/rmw/rmw/macros.h \ + /opt/ros/humble/include/rmw/rmw/ret_types.h \ + /opt/ros/humble/include/rmw/rmw/security_options.h \ + /opt/ros/humble/include/rcl/rcl/arguments.h \ + /opt/ros/humble/include/rcl/rcl/log_level.h \ + /opt/ros/humble/include/rcl/rcl/macros.h \ + /opt/ros/humble/include/rcl/rcl/types.h \ + /opt/ros/humble/include/rmw/rmw/types.h \ + /opt/ros/humble/include/rcutils/rcutils/logging.h \ + /opt/ros/humble/include/rcutils/rcutils/error_handling.h \ + /usr/include/c++/11/stdlib.h /usr/include/string.h \ + /usr/include/strings.h \ + /opt/ros/humble/include/rcutils/rcutils/snprintf.h \ + /opt/ros/humble/include/rcutils/rcutils/time.h \ + /opt/ros/humble/include/rcutils/rcutils/types.h \ + /opt/ros/humble/include/rcutils/rcutils/types/array_list.h \ + /opt/ros/humble/include/rcutils/rcutils/types/char_array.h \ + /opt/ros/humble/include/rcutils/rcutils/types/hash_map.h \ + /opt/ros/humble/include/rcutils/rcutils/types/string_array.h \ + /opt/ros/humble/include/rcutils/rcutils/qsort.h \ + /opt/ros/humble/include/rcutils/rcutils/types/string_map.h \ + /opt/ros/humble/include/rcutils/rcutils/types/uint8_array.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/events_statuses.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/incompatible_qos.h \ + /opt/ros/humble/include/rmw/rmw/qos_policy_kind.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/liveliness_changed.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/liveliness_lost.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/message_lost.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/offered_deadline_missed.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/requested_deadline_missed.h \ + /opt/ros/humble/include/rmw/rmw/serialized_message.h \ + /opt/ros/humble/include/rmw/rmw/subscription_content_filter_options.h \ + /opt/ros/humble/include/rmw/rmw/time.h \ + /opt/ros/humble/include/rcl/rcl/visibility_control.h \ + /opt/ros/humble/include/rcl_yaml_param_parser/rcl_yaml_param_parser/types.h \ + /opt/ros/humble/include/rcl/rcl/init_options.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stdalign.h \ + /opt/ros/humble/include/rcl/rcl/wait.h \ + /opt/ros/humble/include/rcl/rcl/client.h \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/service_type_support_struct.h \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/visibility_control.h \ + /opt/ros/humble/include/rosidl_typesupport_interface/rosidl_typesupport_interface/macros.h \ + /opt/ros/humble/include/rcl/rcl/event_callback.h \ + /opt/ros/humble/include/rmw/rmw/event_callback_type.h \ + /opt/ros/humble/include/rcl/rcl/node.h \ + /opt/ros/humble/include/rcl/rcl/node_options.h \ + /opt/ros/humble/include/rcl/rcl/domain_id.h \ + /opt/ros/humble/include/rcl/rcl/service.h \ + /opt/ros/humble/include/rcl/rcl/subscription.h \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/message_type_support_struct.h \ + /opt/ros/humble/include/rmw/rmw/message_sequence.h \ + /opt/ros/humble/include/rcl/rcl/timer.h \ + /opt/ros/humble/include/rcl/rcl/time.h \ + /opt/ros/humble/include/rmw/rmw/rmw.h \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/sequence_bound.h \ + /opt/ros/humble/include/rmw/rmw/event.h \ + /opt/ros/humble/include/rmw/rmw/publisher_options.h \ + /opt/ros/humble/include/rmw/rmw/qos_profiles.h \ + /opt/ros/humble/include/rmw/rmw/subscription_options.h \ + /opt/ros/humble/include/rcl/rcl/event.h \ + /opt/ros/humble/include/rcl/rcl/publisher.h \ + /opt/ros/humble/include/rcpputils/rcpputils/scope_exit.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/context.hpp \ + /usr/include/c++/11/typeindex /usr/include/c++/11/unordered_set \ + /usr/include/c++/11/bits/unordered_set.h \ + /opt/ros/humble/include/rclcpp/rclcpp/init_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/visibility_control.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/macros.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/contexts/default_context.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/guard_condition.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/executor_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/memory_strategies.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/memory_strategy.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/any_executable.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/callback_group.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/client.hpp \ + /usr/include/c++/11/optional /usr/include/c++/11/sstream \ + /usr/include/c++/11/bits/sstream.tcc /usr/include/c++/11/variant \ + /opt/ros/humble/include/rcl/rcl/error_handling.h \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/cpp_callback_trampoline.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/exceptions.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/exceptions/exceptions.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/join.hpp \ + /usr/include/c++/11/iterator /usr/include/c++/11/bits/stream_iterator.h \ + /opt/ros/humble/include/rclcpp/rclcpp/expand_topic_or_service_name.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/function_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/logging.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/logger.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/filesystem_helper.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/visibility_control.hpp \ + /opt/ros/humble/include/rcutils/rcutils/logging_macros.h \ + /opt/ros/humble/include/rclcpp/rclcpp/utilities.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_graph_interface.hpp \ + /opt/ros/humble/include/rcl/rcl/graph.h \ + /opt/ros/humble/include/rmw/rmw/names_and_types.h \ + /opt/ros/humble/include/rmw/rmw/get_topic_names_and_types.h \ + /opt/ros/humble/include/rmw/rmw/topic_endpoint_info_array.h \ + /opt/ros/humble/include/rmw/rmw/topic_endpoint_info.h \ + /opt/ros/humble/include/rclcpp/rclcpp/event.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/qos.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/duration.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/duration.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/duration__struct.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/bounded_vector.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/message_initialization.hpp \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/message_initialization.h \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/duration__builder.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/duration__traits.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/traits.hpp \ + /usr/include/c++/11/codecvt /usr/include/c++/11/bits/codecvt.h \ + /usr/include/c++/11/iomanip /usr/include/c++/11/locale \ + /usr/include/c++/11/bits/locale_facets_nonio.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/time_members.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/messages_members.h \ + /usr/include/libintl.h /usr/include/c++/11/bits/locale_facets_nonio.tcc \ + /usr/include/c++/11/bits/locale_conv.h \ + /usr/include/c++/11/bits/quoted_string.h \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/duration__type_support.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/rosidl_generator_cpp__visibility_control.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_typesupport_cpp/message_type_support.hpp \ + /opt/ros/humble/include/rcl/rcl/logging_rosout.h \ + /opt/ros/humble/include/rmw/rmw/incompatible_qos_events_statuses.h \ + /opt/ros/humble/include/rclcpp/rclcpp/type_support_decl.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/message_type_support_decl.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/service_type_support_decl.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_typesupport_cpp/service_type_support.hpp \ + /opt/ros/humble/include/rmw/rmw/error_handling.h \ + /opt/ros/humble/include/rmw/rmw/impl/cpp/demangle.hpp \ + /usr/include/c++/11/cxxabi.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/cxxabi_tweaks.h \ + /opt/ros/humble/include/rmw/rmw/impl/config.h \ + /opt/ros/humble/include/rclcpp/rclcpp/publisher_base.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/network_flow_endpoint.hpp \ + /opt/ros/humble/include/rcl/rcl/network_flow_endpoints.h \ + /opt/ros/humble/include/rmw/rmw/network_flow_endpoint.h \ + /opt/ros/humble/include/rmw/rmw/network_flow_endpoint_array.h \ + /opt/ros/humble/include/rclcpp/rclcpp/qos_event.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/waitable.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/time.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/service.hpp \ + /opt/ros/humble/include/tracetools/tracetools/tracetools.h \ + /opt/ros/humble/include/tracetools/tracetools/config.h \ + /opt/ros/humble/include/tracetools/tracetools/visibility_control.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/any_service_callback.hpp \ + /opt/ros/humble/include/tracetools/tracetools/utils.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_base.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/any_subscription_callback.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/allocator/allocator_common.hpp \ + /usr/include/c++/11/cstring \ + /opt/ros/humble/include/rclcpp/rclcpp/allocator/allocator_deleter.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/subscription_callback_type_helper.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/message_info.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/serialized_message.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/type_adapter.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/intra_process_manager.hpp \ + /usr/include/c++/11/shared_mutex \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/ros_message_intra_process_buffer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/subscription_intra_process_base.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/subscription_intra_process.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/buffers/intra_process_buffer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/buffers/buffer_implementation_base.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/subscription_intra_process_buffer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/create_intra_process_buffer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/buffers/ring_buffer_implementation.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/intra_process_buffer_type.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_content_filter_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/timer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/clock.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/time.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/time.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/time__struct.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/time__builder.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/time__traits.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/time__type_support.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/rate.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_base_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/resolve_use_intra_process.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/intra_process_setting.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/resolve_intra_process_buffer_type.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/message_memory_strategy.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/rmw_implementation_specific_subscription_payload.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/rmw_implementation_specific_payload.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/qos_overriding_options.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/set_parameters_result.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/set_parameters_result__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/set_parameters_result__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/set_parameters_result__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/set_parameters_result__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/rosidl_generator_cpp__visibility_control.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/topic_statistics_state.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/topic_statistics/subscription_topic_statistics.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/collector/generate_statistics_message.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/metrics_message.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/metrics_message__struct.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/statistic_data_point__struct.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/metrics_message__builder.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/metrics_message__traits.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/statistic_data_point__traits.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/metrics_message__type_support.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/rosidl_generator_cpp__visibility_control.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/visibility_control.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/moving_average_statistics/types.hpp \ + /usr/include/c++/11/cmath /usr/include/math.h \ + /usr/include/x86_64-linux-gnu/bits/math-vector.h \ + /usr/include/x86_64-linux-gnu/bits/libm-simd-decl-stubs.h \ + /usr/include/x86_64-linux-gnu/bits/flt-eval-method.h \ + /usr/include/x86_64-linux-gnu/bits/fp-logb.h \ + /usr/include/x86_64-linux-gnu/bits/fp-fast.h \ + /usr/include/x86_64-linux-gnu/bits/mathcalls-helper-functions.h \ + /usr/include/x86_64-linux-gnu/bits/mathcalls.h \ + /usr/include/x86_64-linux-gnu/bits/mathcalls-narrow.h \ + /usr/include/x86_64-linux-gnu/bits/iscanonical.h \ + /usr/include/c++/11/bits/specfun.h /usr/include/c++/11/tr1/gamma.tcc \ + /usr/include/c++/11/tr1/special_function_util.h \ + /usr/include/c++/11/tr1/bessel_function.tcc \ + /usr/include/c++/11/tr1/beta_function.tcc \ + /usr/include/c++/11/tr1/ell_integral.tcc \ + /usr/include/c++/11/tr1/exp_integral.tcc \ + /usr/include/c++/11/tr1/hypergeometric.tcc \ + /usr/include/c++/11/tr1/legendre_function.tcc \ + /usr/include/c++/11/tr1/modified_bessel_func.tcc \ + /usr/include/c++/11/tr1/poly_hermite.tcc \ + /usr/include/c++/11/tr1/poly_laguerre.tcc \ + /usr/include/c++/11/tr1/riemann_zeta.tcc \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/constants.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/received_message_age.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/constants.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/collector/collector.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/moving_average_statistics/moving_average.hpp \ + /usr/include/c++/11/numeric /usr/include/c++/11/bits/stl_numeric.h \ + /usr/include/c++/11/pstl/glue_numeric_defs.h \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/moving_average_statistics/types.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/thread_safety_annotations.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/collector/metric_details_interface.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/received_message_period.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/publisher.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/get_message_type_support_handle.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/is_ros_compatible_type.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/loaned_message.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/publisher_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/rmw_implementation_specific_publisher_payload.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/future_return_code.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/executors/single_threaded_executor.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/list_parameters_result.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/list_parameters_result__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/list_parameters_result__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/list_parameters_result__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/list_parameters_result__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter_descriptor.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_descriptor__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/floating_point_range__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/integer_range__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_descriptor__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_descriptor__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/floating_point_range__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/integer_range__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_descriptor__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter_event.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_event__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_value__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_event__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_event__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_value__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_event__type_support.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/generic_publisher.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/shared_library.hpp \ + /opt/ros/humble/include/rcutils/rcutils/shared_library.h \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_topics_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_timers_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/publisher_factory.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_factory.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/typesupport_helpers.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/generic_subscription.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_clock_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_logging_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_parameters_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter__type_support.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_value.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter_type.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_type__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_type__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_type__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_type__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter_value.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_value__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_value__type_support.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_services_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_time_source_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_waitables_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_impl.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_client.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_generic_publisher.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_generic_subscription.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_publisher.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/get_node_topics_interface.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/pointer_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_topics_interface_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/qos_parameters.hpp \ + /opt/ros/humble/include/rmw/rmw/qos_string_conversions.h \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/get_node_parameters_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_parameters_interface_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_service.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_subscription.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/resolve_enable_topic_statistics.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/get_node_timers_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_timers_interface_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_timer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/get_node_base_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_base_interface_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/executors/static_single_threaded_executor.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/executors/static_executor_entities_collector.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/executable_list.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_client.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/describe_parameters.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/describe_parameters__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/describe_parameters__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/describe_parameters__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/describe_parameters__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/get_parameter_types.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameter_types__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameter_types__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameter_types__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameter_types__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/get_parameters.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameters__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameters__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameters__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameters__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/list_parameters.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/list_parameters__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/list_parameters__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/list_parameters__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/list_parameters__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/set_parameters.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/set_parameters_atomically.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters_atomically__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters_atomically__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters_atomically__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters_atomically__type_support.hpp \ + /opt/ros/humble/include/rcl_yaml_param_parser/rcl_yaml_param_parser/parser.h \ + /opt/ros/humble/include/rcl_yaml_param_parser/rcl_yaml_param_parser/visibility_control.h \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_map.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_event_handler.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_service.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/dynamic_storage.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_wait_set_mask.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/detail/storage_policy_common.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/sequential_synchronization.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_result.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_result_kind.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/detail/synchronization_policy_common.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/static_storage.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/thread_safe_synchronization.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/detail/write_preferring_read_write_lock.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_template.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/float64_multi_array.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/float64_multi_array__struct.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/multi_array_layout__struct.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/multi_array_dimension__struct.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/float64_multi_array__builder.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/float64_multi_array__traits.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/multi_array_layout__traits.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/multi_array_dimension__traits.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/float64_multi_array__type_support.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/rosidl_generator_cpp__visibility_control.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/joint_state.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/detail/joint_state__struct.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/header__struct.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/detail/joint_state__builder.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/detail/joint_state__traits.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/header__traits.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/detail/joint_state__type_support.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/rosidl_generator_cpp__visibility_control.hpp \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/arm_define.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_service.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_interface.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_define.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_interface_global.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_version.h diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o new file mode 100644 index 0000000..4b146fe Binary files /dev/null and b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o differ diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o.d b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o.d new file mode 100644 index 0000000..4290474 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o.d @@ -0,0 +1,663 @@ +CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o: \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/src/rm_arm_node.cpp \ + /usr/include/stdc-predef.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/include/rm_arm_node.hpp \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_service.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_interface.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_define.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stdint.h /usr/include/stdint.h \ + /usr/include/x86_64-linux-gnu/bits/libc-header-start.h \ + /usr/include/features.h /usr/include/features-time64.h \ + /usr/include/x86_64-linux-gnu/bits/wordsize.h \ + /usr/include/x86_64-linux-gnu/bits/timesize.h \ + /usr/include/x86_64-linux-gnu/sys/cdefs.h \ + /usr/include/x86_64-linux-gnu/bits/long-double.h \ + /usr/include/x86_64-linux-gnu/gnu/stubs.h \ + /usr/include/x86_64-linux-gnu/gnu/stubs-64.h \ + /usr/include/x86_64-linux-gnu/bits/types.h \ + /usr/include/x86_64-linux-gnu/bits/typesizes.h \ + /usr/include/x86_64-linux-gnu/bits/time64.h \ + /usr/include/x86_64-linux-gnu/bits/wchar.h \ + /usr/include/x86_64-linux-gnu/bits/stdint-intn.h \ + /usr/include/x86_64-linux-gnu/bits/stdint-uintn.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stdbool.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stdarg.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_interface_global.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/rm_version.h \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/include/rm_arm_handler.hpp \ + /usr/include/c++/11/cstdlib \ + /usr/include/x86_64-linux-gnu/c++/11/bits/c++config.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/os_defines.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/cpu_defines.h \ + /usr/include/c++/11/pstl/pstl_config.h /usr/include/stdlib.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stddef.h \ + /usr/include/x86_64-linux-gnu/bits/waitflags.h \ + /usr/include/x86_64-linux-gnu/bits/waitstatus.h \ + /usr/include/x86_64-linux-gnu/bits/floatn.h \ + /usr/include/x86_64-linux-gnu/bits/floatn-common.h \ + /usr/include/x86_64-linux-gnu/bits/types/locale_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__locale_t.h \ + /usr/include/x86_64-linux-gnu/sys/types.h \ + /usr/include/x86_64-linux-gnu/bits/types/clock_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/clockid_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/time_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/timer_t.h /usr/include/endian.h \ + /usr/include/x86_64-linux-gnu/bits/endian.h \ + /usr/include/x86_64-linux-gnu/bits/endianness.h \ + /usr/include/x86_64-linux-gnu/bits/byteswap.h \ + /usr/include/x86_64-linux-gnu/bits/uintn-identity.h \ + /usr/include/x86_64-linux-gnu/sys/select.h \ + /usr/include/x86_64-linux-gnu/bits/select.h \ + /usr/include/x86_64-linux-gnu/bits/types/sigset_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__sigset_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_timeval.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_timespec.h \ + /usr/include/x86_64-linux-gnu/bits/pthreadtypes.h \ + /usr/include/x86_64-linux-gnu/bits/thread-shared-types.h \ + /usr/include/x86_64-linux-gnu/bits/pthreadtypes-arch.h \ + /usr/include/x86_64-linux-gnu/bits/atomic_wide_counter.h \ + /usr/include/x86_64-linux-gnu/bits/struct_mutex.h \ + /usr/include/x86_64-linux-gnu/bits/struct_rwlock.h /usr/include/alloca.h \ + /usr/include/x86_64-linux-gnu/bits/stdlib-float.h \ + /usr/include/c++/11/bits/std_abs.h /usr/include/stdio.h \ + /usr/include/x86_64-linux-gnu/bits/types/__fpos_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__mbstate_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__fpos64_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__FILE.h \ + /usr/include/x86_64-linux-gnu/bits/types/FILE.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_FILE.h \ + /usr/include/x86_64-linux-gnu/bits/types/cookie_io_functions_t.h \ + /usr/include/x86_64-linux-gnu/bits/stdio_lim.h /usr/include/unistd.h \ + /usr/include/x86_64-linux-gnu/bits/posix_opt.h \ + /usr/include/x86_64-linux-gnu/bits/environments.h \ + /usr/include/x86_64-linux-gnu/bits/confname.h \ + /usr/include/x86_64-linux-gnu/bits/getopt_posix.h \ + /usr/include/x86_64-linux-gnu/bits/getopt_core.h \ + /usr/include/x86_64-linux-gnu/bits/unistd_ext.h \ + /usr/include/linux/close_range.h \ + /usr/include/x86_64-linux-gnu/sys/stat.h \ + /usr/include/x86_64-linux-gnu/bits/stat.h \ + /usr/include/x86_64-linux-gnu/bits/struct_stat.h \ + /usr/include/x86_64-linux-gnu/bits/statx.h /usr/include/linux/stat.h \ + /usr/include/linux/types.h /usr/include/x86_64-linux-gnu/asm/types.h \ + /usr/include/asm-generic/types.h /usr/include/asm-generic/int-ll64.h \ + /usr/include/x86_64-linux-gnu/asm/bitsperlong.h \ + /usr/include/asm-generic/bitsperlong.h /usr/include/linux/posix_types.h \ + /usr/include/linux/stddef.h \ + /usr/include/x86_64-linux-gnu/asm/posix_types.h \ + /usr/include/x86_64-linux-gnu/asm/posix_types_64.h \ + /usr/include/asm-generic/posix_types.h \ + /usr/include/x86_64-linux-gnu/bits/statx-generic.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_statx_timestamp.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_statx.h \ + /usr/include/x86_64-linux-gnu/sys/time.h \ + /opt/ros/humble/include/rclcpp/rclcpp/rclcpp.hpp \ + /usr/include/c++/11/csignal /usr/include/signal.h \ + /usr/include/x86_64-linux-gnu/bits/signum-generic.h \ + /usr/include/x86_64-linux-gnu/bits/signum-arch.h \ + /usr/include/x86_64-linux-gnu/bits/types/sig_atomic_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/siginfo_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/__sigval_t.h \ + /usr/include/x86_64-linux-gnu/bits/siginfo-arch.h \ + /usr/include/x86_64-linux-gnu/bits/siginfo-consts.h \ + /usr/include/x86_64-linux-gnu/bits/siginfo-consts-arch.h \ + /usr/include/x86_64-linux-gnu/bits/types/sigval_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/sigevent_t.h \ + /usr/include/x86_64-linux-gnu/bits/sigevent-consts.h \ + /usr/include/x86_64-linux-gnu/bits/sigaction.h \ + /usr/include/x86_64-linux-gnu/bits/sigcontext.h \ + /usr/include/x86_64-linux-gnu/bits/types/stack_t.h \ + /usr/include/x86_64-linux-gnu/sys/ucontext.h \ + /usr/include/x86_64-linux-gnu/bits/sigstack.h \ + /usr/include/x86_64-linux-gnu/bits/sigstksz.h \ + /usr/include/x86_64-linux-gnu/bits/ss_flags.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_sigstack.h \ + /usr/include/x86_64-linux-gnu/bits/sigthread.h \ + /usr/include/x86_64-linux-gnu/bits/signal_ext.h \ + /usr/include/c++/11/memory /usr/include/c++/11/bits/stl_algobase.h \ + /usr/include/c++/11/bits/functexcept.h \ + /usr/include/c++/11/bits/exception_defines.h \ + /usr/include/c++/11/bits/cpp_type_traits.h \ + /usr/include/c++/11/ext/type_traits.h \ + /usr/include/c++/11/ext/numeric_traits.h \ + /usr/include/c++/11/bits/stl_pair.h /usr/include/c++/11/bits/move.h \ + /usr/include/c++/11/type_traits \ + /usr/include/c++/11/bits/stl_iterator_base_types.h \ + /usr/include/c++/11/bits/stl_iterator_base_funcs.h \ + /usr/include/c++/11/bits/concept_check.h \ + /usr/include/c++/11/debug/assertions.h \ + /usr/include/c++/11/bits/stl_iterator.h \ + /usr/include/c++/11/bits/ptr_traits.h /usr/include/c++/11/debug/debug.h \ + /usr/include/c++/11/bits/predefined_ops.h \ + /usr/include/c++/11/bits/allocator.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/c++allocator.h \ + /usr/include/c++/11/ext/new_allocator.h /usr/include/c++/11/new \ + /usr/include/c++/11/bits/exception.h \ + /usr/include/c++/11/bits/memoryfwd.h \ + /usr/include/c++/11/bits/stl_construct.h \ + /usr/include/c++/11/bits/stl_uninitialized.h \ + /usr/include/c++/11/ext/alloc_traits.h \ + /usr/include/c++/11/bits/alloc_traits.h \ + /usr/include/c++/11/bits/stl_tempbuf.h \ + /usr/include/c++/11/bits/stl_raw_storage_iter.h \ + /usr/include/c++/11/bits/align.h /usr/include/c++/11/bit \ + /usr/include/c++/11/bits/uses_allocator.h \ + /usr/include/c++/11/bits/unique_ptr.h /usr/include/c++/11/utility \ + /usr/include/c++/11/bits/stl_relops.h \ + /usr/include/c++/11/initializer_list /usr/include/c++/11/tuple \ + /usr/include/c++/11/array /usr/include/c++/11/bits/range_access.h \ + /usr/include/c++/11/bits/invoke.h \ + /usr/include/c++/11/bits/stl_function.h \ + /usr/include/c++/11/backward/binders.h \ + /usr/include/c++/11/bits/functional_hash.h \ + /usr/include/c++/11/bits/hash_bytes.h \ + /usr/include/c++/11/bits/shared_ptr.h /usr/include/c++/11/iosfwd \ + /usr/include/c++/11/bits/stringfwd.h /usr/include/c++/11/bits/postypes.h \ + /usr/include/c++/11/cwchar /usr/include/wchar.h \ + /usr/include/x86_64-linux-gnu/bits/types/wint_t.h \ + /usr/include/x86_64-linux-gnu/bits/types/mbstate_t.h \ + /usr/include/c++/11/bits/shared_ptr_base.h /usr/include/c++/11/typeinfo \ + /usr/include/c++/11/bits/allocated_ptr.h \ + /usr/include/c++/11/bits/refwrap.h \ + /usr/include/c++/11/ext/aligned_buffer.h \ + /usr/include/c++/11/ext/atomicity.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/gthr.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h \ + /usr/include/pthread.h /usr/include/sched.h \ + /usr/include/x86_64-linux-gnu/bits/sched.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_sched_param.h \ + /usr/include/x86_64-linux-gnu/bits/cpu-set.h /usr/include/time.h \ + /usr/include/x86_64-linux-gnu/bits/time.h \ + /usr/include/x86_64-linux-gnu/bits/timex.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_tm.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct_itimerspec.h \ + /usr/include/x86_64-linux-gnu/bits/setjmp.h \ + /usr/include/x86_64-linux-gnu/bits/types/struct___jmp_buf_tag.h \ + /usr/include/x86_64-linux-gnu/bits/pthread_stack_min-dynamic.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/atomic_word.h \ + /usr/include/x86_64-linux-gnu/sys/single_threaded.h \ + /usr/include/c++/11/ext/concurrence.h /usr/include/c++/11/exception \ + /usr/include/c++/11/bits/exception_ptr.h \ + /usr/include/c++/11/bits/cxxabi_init_exception.h \ + /usr/include/c++/11/bits/nested_exception.h \ + /usr/include/c++/11/bits/shared_ptr_atomic.h \ + /usr/include/c++/11/bits/atomic_base.h \ + /usr/include/c++/11/bits/atomic_lockfree_defines.h \ + /usr/include/c++/11/backward/auto_ptr.h \ + /usr/include/c++/11/pstl/glue_memory_defs.h \ + /usr/include/c++/11/pstl/execution_defs.h \ + /opt/ros/humble/include/rclcpp/rclcpp/executors.hpp \ + /usr/include/c++/11/future /usr/include/c++/11/mutex \ + /usr/include/c++/11/chrono /usr/include/c++/11/ratio \ + /usr/include/c++/11/cstdint /usr/include/c++/11/limits \ + /usr/include/c++/11/ctime /usr/include/c++/11/bits/parse_numbers.h \ + /usr/include/c++/11/system_error \ + /usr/include/x86_64-linux-gnu/c++/11/bits/error_constants.h \ + /usr/include/c++/11/cerrno /usr/include/errno.h \ + /usr/include/x86_64-linux-gnu/bits/errno.h /usr/include/linux/errno.h \ + /usr/include/x86_64-linux-gnu/asm/errno.h \ + /usr/include/asm-generic/errno.h /usr/include/asm-generic/errno-base.h \ + /usr/include/x86_64-linux-gnu/bits/types/error_t.h \ + /usr/include/c++/11/stdexcept /usr/include/c++/11/string \ + /usr/include/c++/11/bits/char_traits.h \ + /usr/include/c++/11/bits/localefwd.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/c++locale.h \ + /usr/include/c++/11/clocale /usr/include/locale.h \ + /usr/include/x86_64-linux-gnu/bits/locale.h /usr/include/c++/11/cctype \ + /usr/include/ctype.h /usr/include/c++/11/bits/ostream_insert.h \ + /usr/include/c++/11/bits/cxxabi_forced.h \ + /usr/include/c++/11/bits/basic_string.h /usr/include/c++/11/string_view \ + /usr/include/c++/11/bits/string_view.tcc \ + /usr/include/c++/11/ext/string_conversions.h /usr/include/c++/11/cstdio \ + /usr/include/c++/11/bits/charconv.h \ + /usr/include/c++/11/bits/basic_string.tcc \ + /usr/include/c++/11/bits/std_mutex.h \ + /usr/include/c++/11/bits/unique_lock.h \ + /usr/include/c++/11/condition_variable /usr/include/c++/11/atomic \ + /usr/include/c++/11/bits/atomic_futex.h \ + /usr/include/c++/11/bits/std_function.h \ + /usr/include/c++/11/bits/std_thread.h \ + /opt/ros/humble/include/rclcpp/rclcpp/executors/multi_threaded_executor.hpp \ + /usr/include/c++/11/set /usr/include/c++/11/bits/stl_tree.h \ + /usr/include/c++/11/bits/node_handle.h \ + /usr/include/c++/11/bits/stl_set.h \ + /usr/include/c++/11/bits/stl_multiset.h \ + /usr/include/c++/11/bits/erase_if.h /usr/include/c++/11/thread \ + /usr/include/c++/11/bits/this_thread_sleep.h \ + /usr/include/c++/11/unordered_map /usr/include/c++/11/bits/hashtable.h \ + /usr/include/c++/11/bits/hashtable_policy.h \ + /usr/include/c++/11/bits/enable_special_members.h \ + /usr/include/c++/11/bits/unordered_map.h \ + /opt/ros/humble/include/rclcpp/rclcpp/executor.hpp \ + /usr/include/c++/11/algorithm /usr/include/c++/11/bits/stl_algo.h \ + /usr/include/c++/11/bits/algorithmfwd.h \ + /usr/include/c++/11/bits/stl_heap.h \ + /usr/include/c++/11/bits/uniform_int_dist.h \ + /usr/include/c++/11/pstl/glue_algorithm_defs.h \ + /usr/include/c++/11/functional /usr/include/c++/11/vector \ + /usr/include/c++/11/bits/stl_vector.h \ + /usr/include/c++/11/bits/stl_bvector.h \ + /usr/include/c++/11/bits/vector.tcc /usr/include/c++/11/cassert \ + /usr/include/assert.h /usr/include/c++/11/iostream \ + /usr/include/c++/11/ostream /usr/include/c++/11/ios \ + /usr/include/c++/11/bits/ios_base.h \ + /usr/include/c++/11/bits/locale_classes.h \ + /usr/include/c++/11/bits/locale_classes.tcc \ + /usr/include/c++/11/streambuf /usr/include/c++/11/bits/streambuf.tcc \ + /usr/include/c++/11/bits/basic_ios.h \ + /usr/include/c++/11/bits/locale_facets.h /usr/include/c++/11/cwctype \ + /usr/include/wctype.h /usr/include/x86_64-linux-gnu/bits/wctype-wchar.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/ctype_base.h \ + /usr/include/c++/11/bits/streambuf_iterator.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/ctype_inline.h \ + /usr/include/c++/11/bits/locale_facets.tcc \ + /usr/include/c++/11/bits/basic_ios.tcc \ + /usr/include/c++/11/bits/ostream.tcc /usr/include/c++/11/istream \ + /usr/include/c++/11/bits/istream.tcc /usr/include/c++/11/list \ + /usr/include/c++/11/bits/stl_list.h /usr/include/c++/11/bits/list.tcc \ + /usr/include/c++/11/map /usr/include/c++/11/bits/stl_map.h \ + /usr/include/c++/11/bits/stl_multimap.h \ + /opt/ros/humble/include/rcl/rcl/guard_condition.h \ + /opt/ros/humble/include/rcl/rcl/allocator.h \ + /opt/ros/humble/include/rcutils/rcutils/allocator.h \ + /opt/ros/humble/include/rcutils/rcutils/macros.h \ + /opt/ros/humble/include/rcutils/rcutils/testing/fault_injection.h \ + /opt/ros/humble/include/rcutils/rcutils/visibility_control.h \ + /opt/ros/humble/include/rcutils/rcutils/visibility_control_macros.h \ + /opt/ros/humble/include/rcutils/rcutils/types/rcutils_ret.h \ + /opt/ros/humble/include/rcl/rcl/context.h \ + /opt/ros/humble/include/rmw/rmw/init.h \ + /opt/ros/humble/include/rmw/rmw/init_options.h \ + /opt/ros/humble/include/rmw/rmw/domain_id.h \ + /opt/ros/humble/include/rmw/rmw/localhost.h \ + /opt/ros/humble/include/rmw/rmw/visibility_control.h \ + /opt/ros/humble/include/rmw/rmw/macros.h \ + /opt/ros/humble/include/rmw/rmw/ret_types.h \ + /opt/ros/humble/include/rmw/rmw/security_options.h \ + /opt/ros/humble/include/rcl/rcl/arguments.h \ + /opt/ros/humble/include/rcl/rcl/log_level.h \ + /opt/ros/humble/include/rcl/rcl/macros.h \ + /opt/ros/humble/include/rcl/rcl/types.h \ + /opt/ros/humble/include/rmw/rmw/types.h \ + /opt/ros/humble/include/rcutils/rcutils/logging.h \ + /opt/ros/humble/include/rcutils/rcutils/error_handling.h \ + /usr/include/c++/11/stdlib.h /usr/include/string.h \ + /usr/include/strings.h \ + /opt/ros/humble/include/rcutils/rcutils/snprintf.h \ + /opt/ros/humble/include/rcutils/rcutils/time.h \ + /opt/ros/humble/include/rcutils/rcutils/types.h \ + /opt/ros/humble/include/rcutils/rcutils/types/array_list.h \ + /opt/ros/humble/include/rcutils/rcutils/types/char_array.h \ + /opt/ros/humble/include/rcutils/rcutils/types/hash_map.h \ + /opt/ros/humble/include/rcutils/rcutils/types/string_array.h \ + /opt/ros/humble/include/rcutils/rcutils/qsort.h \ + /opt/ros/humble/include/rcutils/rcutils/types/string_map.h \ + /opt/ros/humble/include/rcutils/rcutils/types/uint8_array.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/events_statuses.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/incompatible_qos.h \ + /opt/ros/humble/include/rmw/rmw/qos_policy_kind.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/liveliness_changed.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/liveliness_lost.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/message_lost.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/offered_deadline_missed.h \ + /opt/ros/humble/include/rmw/rmw/events_statuses/requested_deadline_missed.h \ + /opt/ros/humble/include/rmw/rmw/serialized_message.h \ + /opt/ros/humble/include/rmw/rmw/subscription_content_filter_options.h \ + /opt/ros/humble/include/rmw/rmw/time.h \ + /opt/ros/humble/include/rcl/rcl/visibility_control.h \ + /opt/ros/humble/include/rcl_yaml_param_parser/rcl_yaml_param_parser/types.h \ + /opt/ros/humble/include/rcl/rcl/init_options.h \ + /usr/lib/gcc/x86_64-linux-gnu/11/include/stdalign.h \ + /opt/ros/humble/include/rcl/rcl/wait.h \ + /opt/ros/humble/include/rcl/rcl/client.h \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/service_type_support_struct.h \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/visibility_control.h \ + /opt/ros/humble/include/rosidl_typesupport_interface/rosidl_typesupport_interface/macros.h \ + /opt/ros/humble/include/rcl/rcl/event_callback.h \ + /opt/ros/humble/include/rmw/rmw/event_callback_type.h \ + /opt/ros/humble/include/rcl/rcl/node.h \ + /opt/ros/humble/include/rcl/rcl/node_options.h \ + /opt/ros/humble/include/rcl/rcl/domain_id.h \ + /opt/ros/humble/include/rcl/rcl/service.h \ + /opt/ros/humble/include/rcl/rcl/subscription.h \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/message_type_support_struct.h \ + /opt/ros/humble/include/rmw/rmw/message_sequence.h \ + /opt/ros/humble/include/rcl/rcl/timer.h \ + /opt/ros/humble/include/rcl/rcl/time.h \ + /opt/ros/humble/include/rmw/rmw/rmw.h \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/sequence_bound.h \ + /opt/ros/humble/include/rmw/rmw/event.h \ + /opt/ros/humble/include/rmw/rmw/publisher_options.h \ + /opt/ros/humble/include/rmw/rmw/qos_profiles.h \ + /opt/ros/humble/include/rmw/rmw/subscription_options.h \ + /opt/ros/humble/include/rcl/rcl/event.h \ + /opt/ros/humble/include/rcl/rcl/publisher.h \ + /opt/ros/humble/include/rcpputils/rcpputils/scope_exit.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/context.hpp \ + /usr/include/c++/11/typeindex /usr/include/c++/11/unordered_set \ + /usr/include/c++/11/bits/unordered_set.h \ + /opt/ros/humble/include/rclcpp/rclcpp/init_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/visibility_control.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/macros.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/contexts/default_context.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/guard_condition.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/executor_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/memory_strategies.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/memory_strategy.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/any_executable.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/callback_group.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/client.hpp \ + /usr/include/c++/11/optional /usr/include/c++/11/sstream \ + /usr/include/c++/11/bits/sstream.tcc /usr/include/c++/11/variant \ + /opt/ros/humble/include/rcl/rcl/error_handling.h \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/cpp_callback_trampoline.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/exceptions.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/exceptions/exceptions.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/join.hpp \ + /usr/include/c++/11/iterator /usr/include/c++/11/bits/stream_iterator.h \ + /opt/ros/humble/include/rclcpp/rclcpp/expand_topic_or_service_name.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/function_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/logging.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/logger.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/filesystem_helper.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/visibility_control.hpp \ + /opt/ros/humble/include/rcutils/rcutils/logging_macros.h \ + /opt/ros/humble/include/rclcpp/rclcpp/utilities.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_graph_interface.hpp \ + /opt/ros/humble/include/rcl/rcl/graph.h \ + /opt/ros/humble/include/rmw/rmw/names_and_types.h \ + /opt/ros/humble/include/rmw/rmw/get_topic_names_and_types.h \ + /opt/ros/humble/include/rmw/rmw/topic_endpoint_info_array.h \ + /opt/ros/humble/include/rmw/rmw/topic_endpoint_info.h \ + /opt/ros/humble/include/rclcpp/rclcpp/event.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/qos.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/duration.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/duration.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/duration__struct.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/bounded_vector.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/message_initialization.hpp \ + /opt/ros/humble/include/rosidl_runtime_c/rosidl_runtime_c/message_initialization.h \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/duration__builder.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/duration__traits.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/traits.hpp \ + /usr/include/c++/11/codecvt /usr/include/c++/11/bits/codecvt.h \ + /usr/include/c++/11/iomanip /usr/include/c++/11/locale \ + /usr/include/c++/11/bits/locale_facets_nonio.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/time_members.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/messages_members.h \ + /usr/include/libintl.h /usr/include/c++/11/bits/locale_facets_nonio.tcc \ + /usr/include/c++/11/bits/locale_conv.h \ + /usr/include/c++/11/bits/quoted_string.h \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/duration__type_support.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/rosidl_generator_cpp__visibility_control.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_typesupport_cpp/message_type_support.hpp \ + /opt/ros/humble/include/rcl/rcl/logging_rosout.h \ + /opt/ros/humble/include/rmw/rmw/incompatible_qos_events_statuses.h \ + /opt/ros/humble/include/rclcpp/rclcpp/type_support_decl.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/message_type_support_decl.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_runtime_cpp/service_type_support_decl.hpp \ + /opt/ros/humble/include/rosidl_runtime_cpp/rosidl_typesupport_cpp/service_type_support.hpp \ + /opt/ros/humble/include/rmw/rmw/error_handling.h \ + /opt/ros/humble/include/rmw/rmw/impl/cpp/demangle.hpp \ + /usr/include/c++/11/cxxabi.h \ + /usr/include/x86_64-linux-gnu/c++/11/bits/cxxabi_tweaks.h \ + /opt/ros/humble/include/rmw/rmw/impl/config.h \ + /opt/ros/humble/include/rclcpp/rclcpp/publisher_base.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/network_flow_endpoint.hpp \ + /opt/ros/humble/include/rcl/rcl/network_flow_endpoints.h \ + /opt/ros/humble/include/rmw/rmw/network_flow_endpoint.h \ + /opt/ros/humble/include/rmw/rmw/network_flow_endpoint_array.h \ + /opt/ros/humble/include/rclcpp/rclcpp/qos_event.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/waitable.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/time.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/service.hpp \ + /opt/ros/humble/include/tracetools/tracetools/tracetools.h \ + /opt/ros/humble/include/tracetools/tracetools/config.h \ + /opt/ros/humble/include/tracetools/tracetools/visibility_control.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/any_service_callback.hpp \ + /opt/ros/humble/include/tracetools/tracetools/utils.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_base.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/any_subscription_callback.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/allocator/allocator_common.hpp \ + /usr/include/c++/11/cstring \ + /opt/ros/humble/include/rclcpp/rclcpp/allocator/allocator_deleter.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/subscription_callback_type_helper.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/message_info.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/serialized_message.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/type_adapter.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/intra_process_manager.hpp \ + /usr/include/c++/11/shared_mutex \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/ros_message_intra_process_buffer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/subscription_intra_process_base.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/subscription_intra_process.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/buffers/intra_process_buffer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/buffers/buffer_implementation_base.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/subscription_intra_process_buffer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/create_intra_process_buffer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/buffers/ring_buffer_implementation.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/intra_process_buffer_type.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_content_filter_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/timer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/clock.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/time.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/time.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/time__struct.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/time__builder.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/time__traits.hpp \ + /opt/ros/humble/include/builtin_interfaces/builtin_interfaces/msg/detail/time__type_support.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/rate.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_base_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/resolve_use_intra_process.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/intra_process_setting.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/resolve_intra_process_buffer_type.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/message_memory_strategy.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/rmw_implementation_specific_subscription_payload.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/rmw_implementation_specific_payload.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/qos_overriding_options.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/set_parameters_result.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/set_parameters_result__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/set_parameters_result__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/set_parameters_result__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/set_parameters_result__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/rosidl_generator_cpp__visibility_control.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/topic_statistics_state.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/topic_statistics/subscription_topic_statistics.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/collector/generate_statistics_message.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/metrics_message.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/metrics_message__struct.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/statistic_data_point__struct.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/metrics_message__builder.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/metrics_message__traits.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/statistic_data_point__traits.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/detail/metrics_message__type_support.hpp \ + /opt/ros/humble/include/statistics_msgs/statistics_msgs/msg/rosidl_generator_cpp__visibility_control.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/visibility_control.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/moving_average_statistics/types.hpp \ + /usr/include/c++/11/cmath /usr/include/math.h \ + /usr/include/x86_64-linux-gnu/bits/math-vector.h \ + /usr/include/x86_64-linux-gnu/bits/libm-simd-decl-stubs.h \ + /usr/include/x86_64-linux-gnu/bits/flt-eval-method.h \ + /usr/include/x86_64-linux-gnu/bits/fp-logb.h \ + /usr/include/x86_64-linux-gnu/bits/fp-fast.h \ + /usr/include/x86_64-linux-gnu/bits/mathcalls-helper-functions.h \ + /usr/include/x86_64-linux-gnu/bits/mathcalls.h \ + /usr/include/x86_64-linux-gnu/bits/mathcalls-narrow.h \ + /usr/include/x86_64-linux-gnu/bits/iscanonical.h \ + /usr/include/c++/11/bits/specfun.h /usr/include/c++/11/tr1/gamma.tcc \ + /usr/include/c++/11/tr1/special_function_util.h \ + /usr/include/c++/11/tr1/bessel_function.tcc \ + /usr/include/c++/11/tr1/beta_function.tcc \ + /usr/include/c++/11/tr1/ell_integral.tcc \ + /usr/include/c++/11/tr1/exp_integral.tcc \ + /usr/include/c++/11/tr1/hypergeometric.tcc \ + /usr/include/c++/11/tr1/legendre_function.tcc \ + /usr/include/c++/11/tr1/modified_bessel_func.tcc \ + /usr/include/c++/11/tr1/poly_hermite.tcc \ + /usr/include/c++/11/tr1/poly_laguerre.tcc \ + /usr/include/c++/11/tr1/riemann_zeta.tcc \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/constants.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/received_message_age.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/constants.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/collector/collector.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/moving_average_statistics/moving_average.hpp \ + /usr/include/c++/11/numeric /usr/include/c++/11/bits/stl_numeric.h \ + /usr/include/c++/11/pstl/glue_numeric_defs.h \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/moving_average_statistics/types.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/thread_safety_annotations.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/collector/metric_details_interface.hpp \ + /opt/ros/humble/include/libstatistics_collector/libstatistics_collector/topic_statistics_collector/received_message_period.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/publisher.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/get_message_type_support_handle.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/is_ros_compatible_type.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/loaned_message.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/publisher_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/rmw_implementation_specific_publisher_payload.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/future_return_code.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/executors/single_threaded_executor.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/list_parameters_result.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/list_parameters_result__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/list_parameters_result__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/list_parameters_result__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/list_parameters_result__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter_descriptor.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_descriptor__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/floating_point_range__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/integer_range__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_descriptor__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_descriptor__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/floating_point_range__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/integer_range__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_descriptor__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter_event.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_event__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_value__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_event__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_event__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_value__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_event__type_support.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/generic_publisher.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/shared_library.hpp \ + /opt/ros/humble/include/rcutils/rcutils/shared_library.h \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_topics_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_timers_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/publisher_factory.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_factory.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/typesupport_helpers.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/generic_subscription.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_clock_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_logging_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_parameters_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter__type_support.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_value.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter_type.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_type__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_type__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_type__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_type__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/parameter_value.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_value__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/msg/detail/parameter_value__type_support.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_services_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_time_source_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_waitables_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_options.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_impl.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_client.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_generic_publisher.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_generic_subscription.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_publisher.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/get_node_topics_interface.hpp \ + /opt/ros/humble/include/rcpputils/rcpputils/pointer_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_topics_interface_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/qos_parameters.hpp \ + /opt/ros/humble/include/rmw/rmw/qos_string_conversions.h \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/get_node_parameters_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_parameters_interface_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_service.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_subscription.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/detail/resolve_enable_topic_statistics.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/get_node_timers_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_timers_interface_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/create_timer.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/get_node_base_interface.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/node_interfaces/node_base_interface_traits.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/executors/static_single_threaded_executor.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/executors/static_executor_entities_collector.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/experimental/executable_list.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_client.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/describe_parameters.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/describe_parameters__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/describe_parameters__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/describe_parameters__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/describe_parameters__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/get_parameter_types.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameter_types__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameter_types__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameter_types__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameter_types__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/get_parameters.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameters__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameters__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameters__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/get_parameters__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/list_parameters.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/list_parameters__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/list_parameters__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/list_parameters__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/list_parameters__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/set_parameters.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters__type_support.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/set_parameters_atomically.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters_atomically__struct.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters_atomically__builder.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters_atomically__traits.hpp \ + /opt/ros/humble/include/rcl_interfaces/rcl_interfaces/srv/detail/set_parameters_atomically__type_support.hpp \ + /opt/ros/humble/include/rcl_yaml_param_parser/rcl_yaml_param_parser/parser.h \ + /opt/ros/humble/include/rcl_yaml_param_parser/rcl_yaml_param_parser/visibility_control.h \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_map.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_event_handler.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/parameter_service.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/dynamic_storage.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/subscription_wait_set_mask.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/detail/storage_policy_common.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/sequential_synchronization.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_result.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_result_kind.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/detail/synchronization_policy_common.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/static_storage.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/thread_safe_synchronization.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_policies/detail/write_preferring_read_write_lock.hpp \ + /opt/ros/humble/include/rclcpp/rclcpp/wait_set_template.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/float64_multi_array.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/float64_multi_array__struct.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/multi_array_layout__struct.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/multi_array_dimension__struct.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/float64_multi_array__builder.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/float64_multi_array__traits.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/multi_array_layout__traits.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/multi_array_dimension__traits.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/float64_multi_array__type_support.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/rosidl_generator_cpp__visibility_control.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/joint_state.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/detail/joint_state__struct.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/header__struct.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/detail/joint_state__builder.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/detail/joint_state__traits.hpp \ + /opt/ros/humble/include/std_msgs/std_msgs/msg/detail/header__traits.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/detail/joint_state__type_support.hpp \ + /opt/ros/humble/include/sensor_msgs/sensor_msgs/msg/rosidl_generator_cpp__visibility_control.hpp \ + /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/../../include/arm_define.h diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/DependInfo.cmake b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/DependInfo.cmake new file mode 100644 index 0000000..dc55e44 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/DependInfo.cmake @@ -0,0 +1,18 @@ + +# Consider dependencies only in project. +set(CMAKE_DEPENDS_IN_PROJECT_ONLY OFF) + +# The set of languages for which implicit dependencies are needed: +set(CMAKE_DEPENDS_LANGUAGES + ) + +# The set of dependency files which are needed: +set(CMAKE_DEPENDS_DEPENDENCY_FILES + ) + +# Targets to which this target links. +set(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# Fortran module output directory. +set(CMAKE_Fortran_TARGET_MODULE_DIR "") diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/build.make b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/build.make new file mode 100644 index 0000000..9c0af7f --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/build.make @@ -0,0 +1,87 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 3.22 + +# Delete rule output on recipe failure. +.DELETE_ON_ERROR: + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Disable VCS-based implicit rules. +% : %,v + +# Disable VCS-based implicit rules. +% : RCS/% + +# Disable VCS-based implicit rules. +% : RCS/%,v + +# Disable VCS-based implicit rules. +% : SCCS/s.% + +# Disable VCS-based implicit rules. +% : s.% + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Command-line flag to silence nested $(MAKE). +$(VERBOSE)MAKESILENT = -s + +#Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E rm -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build + +# Utility rule file for rm_arm_control_uninstall. + +# Include any custom commands dependencies for this target. +include CMakeFiles/rm_arm_control_uninstall.dir/compiler_depend.make + +# Include the progress variables for this target. +include CMakeFiles/rm_arm_control_uninstall.dir/progress.make + +CMakeFiles/rm_arm_control_uninstall: + /usr/bin/cmake -P /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_uninstall_target/ament_cmake_uninstall_target.cmake + +rm_arm_control_uninstall: CMakeFiles/rm_arm_control_uninstall +rm_arm_control_uninstall: CMakeFiles/rm_arm_control_uninstall.dir/build.make +.PHONY : rm_arm_control_uninstall + +# Rule to build all files generated by this target. +CMakeFiles/rm_arm_control_uninstall.dir/build: rm_arm_control_uninstall +.PHONY : CMakeFiles/rm_arm_control_uninstall.dir/build + +CMakeFiles/rm_arm_control_uninstall.dir/clean: + $(CMAKE_COMMAND) -P CMakeFiles/rm_arm_control_uninstall.dir/cmake_clean.cmake +.PHONY : CMakeFiles/rm_arm_control_uninstall.dir/clean + +CMakeFiles/rm_arm_control_uninstall.dir/depend: + cd /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/DependInfo.cmake --color=$(COLOR) +.PHONY : CMakeFiles/rm_arm_control_uninstall.dir/depend + diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/cmake_clean.cmake b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/cmake_clean.cmake new file mode 100644 index 0000000..4e9f1ff --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/cmake_clean.cmake @@ -0,0 +1,8 @@ +file(REMOVE_RECURSE + "CMakeFiles/rm_arm_control_uninstall" +) + +# Per-language clean rules from dependency scanning. +foreach(lang ) + include(CMakeFiles/rm_arm_control_uninstall.dir/cmake_clean_${lang}.cmake OPTIONAL) +endforeach() diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/compiler_depend.make b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/compiler_depend.make new file mode 100644 index 0000000..a2bffc5 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/compiler_depend.make @@ -0,0 +1,2 @@ +# Empty custom commands generated dependencies file for rm_arm_control_uninstall. +# This may be replaced when dependencies are built. diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/compiler_depend.ts b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/compiler_depend.ts new file mode 100644 index 0000000..9a815f6 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/compiler_depend.ts @@ -0,0 +1,2 @@ +# CMAKE generated file: DO NOT EDIT! +# Timestamp file for custom commands dependencies management for rm_arm_control_uninstall. diff --git a/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/progress.make b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/progress.make new file mode 100644 index 0000000..8b13789 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/rm_arm_control_uninstall.dir/progress.make @@ -0,0 +1 @@ + diff --git a/rm_arm_control/build/CMakeFiles/uninstall.dir/DependInfo.cmake b/rm_arm_control/build/CMakeFiles/uninstall.dir/DependInfo.cmake new file mode 100644 index 0000000..dc55e44 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/uninstall.dir/DependInfo.cmake @@ -0,0 +1,18 @@ + +# Consider dependencies only in project. +set(CMAKE_DEPENDS_IN_PROJECT_ONLY OFF) + +# The set of languages for which implicit dependencies are needed: +set(CMAKE_DEPENDS_LANGUAGES + ) + +# The set of dependency files which are needed: +set(CMAKE_DEPENDS_DEPENDENCY_FILES + ) + +# Targets to which this target links. +set(CMAKE_TARGET_LINKED_INFO_FILES + ) + +# Fortran module output directory. +set(CMAKE_Fortran_TARGET_MODULE_DIR "") diff --git a/rm_arm_control/build/CMakeFiles/uninstall.dir/build.make b/rm_arm_control/build/CMakeFiles/uninstall.dir/build.make new file mode 100644 index 0000000..02dda5c --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/uninstall.dir/build.make @@ -0,0 +1,83 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 3.22 + +# Delete rule output on recipe failure. +.DELETE_ON_ERROR: + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Disable VCS-based implicit rules. +% : %,v + +# Disable VCS-based implicit rules. +% : RCS/% + +# Disable VCS-based implicit rules. +% : RCS/%,v + +# Disable VCS-based implicit rules. +% : SCCS/s.% + +# Disable VCS-based implicit rules. +% : s.% + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Command-line flag to silence nested $(MAKE). +$(VERBOSE)MAKESILENT = -s + +#Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E rm -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build + +# Utility rule file for uninstall. + +# Include any custom commands dependencies for this target. +include CMakeFiles/uninstall.dir/compiler_depend.make + +# Include the progress variables for this target. +include CMakeFiles/uninstall.dir/progress.make + +uninstall: CMakeFiles/uninstall.dir/build.make +.PHONY : uninstall + +# Rule to build all files generated by this target. +CMakeFiles/uninstall.dir/build: uninstall +.PHONY : CMakeFiles/uninstall.dir/build + +CMakeFiles/uninstall.dir/clean: + $(CMAKE_COMMAND) -P CMakeFiles/uninstall.dir/cmake_clean.cmake +.PHONY : CMakeFiles/uninstall.dir/clean + +CMakeFiles/uninstall.dir/depend: + cd /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build && $(CMAKE_COMMAND) -E cmake_depends "Unix Makefiles" /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles/uninstall.dir/DependInfo.cmake --color=$(COLOR) +.PHONY : CMakeFiles/uninstall.dir/depend + diff --git a/rm_arm_control/build/CMakeFiles/uninstall.dir/cmake_clean.cmake b/rm_arm_control/build/CMakeFiles/uninstall.dir/cmake_clean.cmake new file mode 100644 index 0000000..9960e98 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/uninstall.dir/cmake_clean.cmake @@ -0,0 +1,5 @@ + +# Per-language clean rules from dependency scanning. +foreach(lang ) + include(CMakeFiles/uninstall.dir/cmake_clean_${lang}.cmake OPTIONAL) +endforeach() diff --git a/rm_arm_control/build/CMakeFiles/uninstall.dir/compiler_depend.make b/rm_arm_control/build/CMakeFiles/uninstall.dir/compiler_depend.make new file mode 100644 index 0000000..2d74447 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/uninstall.dir/compiler_depend.make @@ -0,0 +1,2 @@ +# Empty custom commands generated dependencies file for uninstall. +# This may be replaced when dependencies are built. diff --git a/rm_arm_control/build/CMakeFiles/uninstall.dir/compiler_depend.ts b/rm_arm_control/build/CMakeFiles/uninstall.dir/compiler_depend.ts new file mode 100644 index 0000000..ef27dcc --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/uninstall.dir/compiler_depend.ts @@ -0,0 +1,2 @@ +# CMAKE generated file: DO NOT EDIT! +# Timestamp file for custom commands dependencies management for uninstall. diff --git a/rm_arm_control/build/CMakeFiles/uninstall.dir/progress.make b/rm_arm_control/build/CMakeFiles/uninstall.dir/progress.make new file mode 100644 index 0000000..8b13789 --- /dev/null +++ b/rm_arm_control/build/CMakeFiles/uninstall.dir/progress.make @@ -0,0 +1 @@ + diff --git a/rm_arm_control/build/CTestConfiguration.ini b/rm_arm_control/build/CTestConfiguration.ini new file mode 100644 index 0000000..6875b86 --- /dev/null +++ b/rm_arm_control/build/CTestConfiguration.ini @@ -0,0 +1,105 @@ +# This file is configured by CMake automatically as DartConfiguration.tcl +# If you choose not to use CMake, this file may be hand configured, by +# filling in the required variables. + + +# Configuration directories and files +SourceDirectory: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control +BuildDirectory: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build + +# Where to place the cost data store +CostDataFile: + +# Site is something like machine.domain, i.e. pragmatic.crd +Site: zj-OMEN-Gaming-Laptop-16-am0xxx + +# Build name is osname-revision-compiler, i.e. Linux-2.4.2-2smp-c++ +BuildName: + +# Subprojects +LabelsForSubprojects: + +# Submission information +SubmitURL: + +# Dashboard start time +NightlyStartTime: + +# Commands for the build/test/submit cycle +ConfigureCommand: "/usr/bin/cmake" "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control" +MakeCommand: +DefaultCTestConfigurationType: + +# version control +UpdateVersionOnly: + +# CVS options +# Default is "-d -P -A" +CVSCommand: +CVSUpdateOptions: + +# Subversion options +SVNCommand: +SVNOptions: +SVNUpdateOptions: + +# Git options +GITCommand: +GITInitSubmodules: +GITUpdateOptions: +GITUpdateCustom: + +# Perforce options +P4Command: +P4Client: +P4Options: +P4UpdateOptions: +P4UpdateCustom: + +# Generic update command +UpdateCommand: +UpdateOptions: +UpdateType: + +# Compiler info +Compiler: /usr/bin/c++ +CompilerVersion: 11.4.0 + +# Dynamic analysis (MemCheck) +PurifyCommand: +ValgrindCommand: +ValgrindCommandOptions: +DrMemoryCommand: +DrMemoryCommandOptions: +CudaSanitizerCommand: +CudaSanitizerCommandOptions: +MemoryCheckType: +MemoryCheckSanitizerOptions: +MemoryCheckCommand: +MemoryCheckCommandOptions: +MemoryCheckSuppressionFile: + +# Coverage +CoverageCommand: +CoverageExtraFlags: + +# Testing options +# TimeOut is the amount of time in seconds to wait for processes +# to complete during testing. After TimeOut seconds, the +# process will be summarily terminated. +# Currently set to 25 minutes +TimeOut: + +# During parallel testing CTest will not start a new test if doing +# so would cause the system load to exceed this value. +TestLoad: + +UseLaunchers: +CurlOptions: +# warning, if you add new options here that have to do with submit, +# you have to update cmCTestSubmitCommand.cxx + +# For CTest submissions that timeout, these options +# specify behavior for retrying the submission +CTestSubmitRetryDelay: +CTestSubmitRetryCount: diff --git a/rm_arm_control/build/CTestCustom.cmake b/rm_arm_control/build/CTestCustom.cmake new file mode 100644 index 0000000..14956f3 --- /dev/null +++ b/rm_arm_control/build/CTestCustom.cmake @@ -0,0 +1,2 @@ +set(CTEST_CUSTOM_MAXIMUM_PASSED_TEST_OUTPUT_SIZE 0) +set(CTEST_CUSTOM_MAXIMUM_FAILED_TEST_OUTPUT_SIZE 0) diff --git a/rm_arm_control/build/CTestTestfile.cmake b/rm_arm_control/build/CTestTestfile.cmake new file mode 100644 index 0000000..90045a5 --- /dev/null +++ b/rm_arm_control/build/CTestTestfile.cmake @@ -0,0 +1,6 @@ +# CMake generated Testfile for +# Source directory: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control +# Build directory: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build +# +# This file includes the relevant testing commands required for +# testing this directory and lists subdirectories to be tested as well. diff --git a/rm_arm_control/build/Makefile b/rm_arm_control/build/Makefile new file mode 100644 index 0000000..9f1bf31 --- /dev/null +++ b/rm_arm_control/build/Makefile @@ -0,0 +1,296 @@ +# CMAKE generated file: DO NOT EDIT! +# Generated by "Unix Makefiles" Generator, CMake Version 3.22 + +# Default target executed when no arguments are given to make. +default_target: all +.PHONY : default_target + +# Allow only one "make -f Makefile2" at a time, but pass parallelism. +.NOTPARALLEL: + +#============================================================================= +# Special targets provided by cmake. + +# Disable implicit rules so canonical targets will work. +.SUFFIXES: + +# Disable VCS-based implicit rules. +% : %,v + +# Disable VCS-based implicit rules. +% : RCS/% + +# Disable VCS-based implicit rules. +% : RCS/%,v + +# Disable VCS-based implicit rules. +% : SCCS/s.% + +# Disable VCS-based implicit rules. +% : s.% + +.SUFFIXES: .hpux_make_needs_suffix_list + +# Command-line flag to silence nested $(MAKE). +$(VERBOSE)MAKESILENT = -s + +#Suppress display of executed commands. +$(VERBOSE).SILENT: + +# A target that is always out of date. +cmake_force: +.PHONY : cmake_force + +#============================================================================= +# Set environment variables for the build. + +# The shell in which to execute make rules. +SHELL = /bin/sh + +# The CMake executable. +CMAKE_COMMAND = /usr/bin/cmake + +# The command to remove a file. +RM = /usr/bin/cmake -E rm -f + +# Escaping for special characters. +EQUALS = = + +# The top-level source directory on which CMake was run. +CMAKE_SOURCE_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control + +# The top-level build directory on which CMake was run. +CMAKE_BINARY_DIR = /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build + +#============================================================================= +# Targets provided globally by CMake. + +# Special rule for the target test +test: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running tests..." + /usr/bin/ctest --force-new-ctest-process $(ARGS) +.PHONY : test + +# Special rule for the target test +test/fast: test +.PHONY : test/fast + +# Special rule for the target edit_cache +edit_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "No interactive CMake dialog available..." + /usr/bin/cmake -E echo No\ interactive\ CMake\ dialog\ available. +.PHONY : edit_cache + +# Special rule for the target edit_cache +edit_cache/fast: edit_cache +.PHONY : edit_cache/fast + +# Special rule for the target rebuild_cache +rebuild_cache: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Running CMake to regenerate build system..." + /usr/bin/cmake --regenerate-during-build -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) +.PHONY : rebuild_cache + +# Special rule for the target rebuild_cache +rebuild_cache/fast: rebuild_cache +.PHONY : rebuild_cache/fast + +# Special rule for the target list_install_components +list_install_components: + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Available install components are: \"Unspecified\"" +.PHONY : list_install_components + +# Special rule for the target list_install_components +list_install_components/fast: list_install_components +.PHONY : list_install_components/fast + +# Special rule for the target install +install: preinstall + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..." + /usr/bin/cmake -P cmake_install.cmake +.PHONY : install + +# Special rule for the target install +install/fast: preinstall/fast + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Install the project..." + /usr/bin/cmake -P cmake_install.cmake +.PHONY : install/fast + +# Special rule for the target install/local +install/local: preinstall + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..." + /usr/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake +.PHONY : install/local + +# Special rule for the target install/local +install/local/fast: preinstall/fast + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing only the local directory..." + /usr/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake +.PHONY : install/local/fast + +# Special rule for the target install/strip +install/strip: preinstall + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..." + /usr/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake +.PHONY : install/strip + +# Special rule for the target install/strip +install/strip/fast: preinstall/fast + @$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan "Installing the project stripped..." + /usr/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake +.PHONY : install/strip/fast + +# The main all target +all: cmake_check_build_system + $(CMAKE_COMMAND) -E cmake_progress_start /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build//CMakeFiles/progress.marks + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 all + $(CMAKE_COMMAND) -E cmake_progress_start /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/CMakeFiles 0 +.PHONY : all + +# The main clean target +clean: + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 clean +.PHONY : clean + +# The main clean target +clean/fast: clean +.PHONY : clean/fast + +# Prepare targets for installation. +preinstall: all + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall + +# Prepare targets for installation. +preinstall/fast: + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 preinstall +.PHONY : preinstall/fast + +# clear depends +depend: + $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1 +.PHONY : depend + +#============================================================================= +# Target rules for targets named uninstall + +# Build rule for target. +uninstall: cmake_check_build_system + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 uninstall +.PHONY : uninstall + +# fast build rule for target. +uninstall/fast: + $(MAKE) $(MAKESILENT) -f CMakeFiles/uninstall.dir/build.make CMakeFiles/uninstall.dir/build +.PHONY : uninstall/fast + +#============================================================================= +# Target rules for targets named rm_arm_control_uninstall + +# Build rule for target. +rm_arm_control_uninstall: cmake_check_build_system + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 rm_arm_control_uninstall +.PHONY : rm_arm_control_uninstall + +# fast build rule for target. +rm_arm_control_uninstall/fast: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control_uninstall.dir/build.make CMakeFiles/rm_arm_control_uninstall.dir/build +.PHONY : rm_arm_control_uninstall/fast + +#============================================================================= +# Target rules for targets named rm_arm_control + +# Build rule for target. +rm_arm_control: cmake_check_build_system + $(MAKE) $(MAKESILENT) -f CMakeFiles/Makefile2 rm_arm_control +.PHONY : rm_arm_control + +# fast build rule for target. +rm_arm_control/fast: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/build +.PHONY : rm_arm_control/fast + +src/rm_arm_handler.o: src/rm_arm_handler.cpp.o +.PHONY : src/rm_arm_handler.o + +# target to build an object file +src/rm_arm_handler.cpp.o: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.o +.PHONY : src/rm_arm_handler.cpp.o + +src/rm_arm_handler.i: src/rm_arm_handler.cpp.i +.PHONY : src/rm_arm_handler.i + +# target to preprocess a source file +src/rm_arm_handler.cpp.i: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.i +.PHONY : src/rm_arm_handler.cpp.i + +src/rm_arm_handler.s: src/rm_arm_handler.cpp.s +.PHONY : src/rm_arm_handler.s + +# target to generate assembly for a file +src/rm_arm_handler.cpp.s: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/src/rm_arm_handler.cpp.s +.PHONY : src/rm_arm_handler.cpp.s + +src/rm_arm_node.o: src/rm_arm_node.cpp.o +.PHONY : src/rm_arm_node.o + +# target to build an object file +src/rm_arm_node.cpp.o: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.o +.PHONY : src/rm_arm_node.cpp.o + +src/rm_arm_node.i: src/rm_arm_node.cpp.i +.PHONY : src/rm_arm_node.i + +# target to preprocess a source file +src/rm_arm_node.cpp.i: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.i +.PHONY : src/rm_arm_node.cpp.i + +src/rm_arm_node.s: src/rm_arm_node.cpp.s +.PHONY : src/rm_arm_node.s + +# target to generate assembly for a file +src/rm_arm_node.cpp.s: + $(MAKE) $(MAKESILENT) -f CMakeFiles/rm_arm_control.dir/build.make CMakeFiles/rm_arm_control.dir/src/rm_arm_node.cpp.s +.PHONY : src/rm_arm_node.cpp.s + +# Help Target +help: + @echo "The following are some of the valid targets for this Makefile:" + @echo "... all (the default if no target is provided)" + @echo "... clean" + @echo "... depend" + @echo "... edit_cache" + @echo "... install" + @echo "... install/local" + @echo "... install/strip" + @echo "... list_install_components" + @echo "... rebuild_cache" + @echo "... test" + @echo "... rm_arm_control_uninstall" + @echo "... uninstall" + @echo "... rm_arm_control" + @echo "... src/rm_arm_handler.o" + @echo "... src/rm_arm_handler.i" + @echo "... src/rm_arm_handler.s" + @echo "... src/rm_arm_node.o" + @echo "... src/rm_arm_node.i" + @echo "... src/rm_arm_node.s" +.PHONY : help + + + +#============================================================================= +# Special targets to cleanup operation of make. + +# Special rule to run CMake to check the build system integrity. +# No rule that depends on this can have commands that come from listfiles +# because they might be regenerated. +cmake_check_build_system: + $(CMAKE_COMMAND) -S$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0 +.PHONY : cmake_check_build_system + diff --git a/rm_arm_control/build/ament_cmake_core/package.cmake b/rm_arm_control/build/ament_cmake_core/package.cmake new file mode 100644 index 0000000..0604128 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/package.cmake @@ -0,0 +1,14 @@ +set(_AMENT_PACKAGE_NAME "rm_arm_control") +set(rm_arm_control_VERSION "1.0.0") +set(rm_arm_control_MAINTAINER "Your Name ") +set(rm_arm_control_BUILD_DEPENDS "ament_cmake") +set(rm_arm_control_BUILDTOOL_DEPENDS ) +set(rm_arm_control_BUILD_EXPORT_DEPENDS ) +set(rm_arm_control_BUILDTOOL_EXPORT_DEPENDS ) +set(rm_arm_control_EXEC_DEPENDS "rclcpp" "geometry_msgs" "nav_msgs" "ros2launch") +set(rm_arm_control_TEST_DEPENDS ) +set(rm_arm_control_GROUP_DEPENDS ) +set(rm_arm_control_MEMBER_OF_GROUPS ) +set(rm_arm_control_DEPRECATED "") +set(rm_arm_control_EXPORT_TAGS) +list(APPEND rm_arm_control_EXPORT_TAGS "ament_cmake") diff --git a/rm_arm_control/build/ament_cmake_core/rm_arm_controlConfig-version.cmake b/rm_arm_control/build/ament_cmake_core/rm_arm_controlConfig-version.cmake new file mode 100644 index 0000000..1a5b413 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/rm_arm_controlConfig-version.cmake @@ -0,0 +1,14 @@ +# generated from ament/cmake/core/templates/nameConfig-version.cmake.in +set(PACKAGE_VERSION "1.0.0") + +set(PACKAGE_VERSION_EXACT False) +set(PACKAGE_VERSION_COMPATIBLE False) + +if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_EXACT True) + set(PACKAGE_VERSION_COMPATIBLE True) +endif() + +if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_COMPATIBLE True) +endif() diff --git a/rm_arm_control/build/ament_cmake_core/rm_arm_controlConfig.cmake b/rm_arm_control/build/ament_cmake_core/rm_arm_controlConfig.cmake new file mode 100644 index 0000000..eca9a69 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/rm_arm_controlConfig.cmake @@ -0,0 +1,42 @@ +# generated from ament/cmake/core/templates/nameConfig.cmake.in + +# prevent multiple inclusion +if(_rm_arm_control_CONFIG_INCLUDED) + # ensure to keep the found flag the same + if(NOT DEFINED rm_arm_control_FOUND) + # explicitly set it to FALSE, otherwise CMake will set it to TRUE + set(rm_arm_control_FOUND FALSE) + elseif(NOT rm_arm_control_FOUND) + # use separate condition to avoid uninitialized variable warning + set(rm_arm_control_FOUND FALSE) + endif() + return() +endif() +set(_rm_arm_control_CONFIG_INCLUDED TRUE) + +# output package information +if(NOT rm_arm_control_FIND_QUIETLY) + message(STATUS "Found rm_arm_control: 1.0.0 (${rm_arm_control_DIR})") +endif() + +# warn when using a deprecated package +if(NOT "" STREQUAL "") + set(_msg "Package 'rm_arm_control' is deprecated") + # append custom deprecation text if available + if(NOT "" STREQUAL "TRUE") + set(_msg "${_msg} ()") + endif() + # optionally quiet the deprecation message + if(NOT ${rm_arm_control_DEPRECATED_QUIET}) + message(DEPRECATION "${_msg}") + endif() +endif() + +# flag package as ament-based to distinguish it after being find_package()-ed +set(rm_arm_control_FOUND_AMENT_PACKAGE TRUE) + +# include all config extra files +set(_extras "") +foreach(_extra ${_extras}) + include("${rm_arm_control_DIR}/${_extra}") +endforeach() diff --git a/rm_arm_control/build/ament_cmake_core/stamps/ament_prefix_path.sh.stamp b/rm_arm_control/build/ament_cmake_core/stamps/ament_prefix_path.sh.stamp new file mode 100644 index 0000000..02e441b --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/stamps/ament_prefix_path.sh.stamp @@ -0,0 +1,4 @@ +# copied from +# ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh + +ament_prepend_unique_value AMENT_PREFIX_PATH "$AMENT_CURRENT_PREFIX" diff --git a/rm_arm_control/build/ament_cmake_core/stamps/nameConfig-version.cmake.in.stamp b/rm_arm_control/build/ament_cmake_core/stamps/nameConfig-version.cmake.in.stamp new file mode 100644 index 0000000..ee49c9f --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/stamps/nameConfig-version.cmake.in.stamp @@ -0,0 +1,14 @@ +# generated from ament/cmake/core/templates/nameConfig-version.cmake.in +set(PACKAGE_VERSION "@PACKAGE_VERSION@") + +set(PACKAGE_VERSION_EXACT False) +set(PACKAGE_VERSION_COMPATIBLE False) + +if("${PACKAGE_FIND_VERSION}" VERSION_EQUAL "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_EXACT True) + set(PACKAGE_VERSION_COMPATIBLE True) +endif() + +if("${PACKAGE_FIND_VERSION}" VERSION_LESS "${PACKAGE_VERSION}") + set(PACKAGE_VERSION_COMPATIBLE True) +endif() diff --git a/rm_arm_control/build/ament_cmake_core/stamps/nameConfig.cmake.in.stamp b/rm_arm_control/build/ament_cmake_core/stamps/nameConfig.cmake.in.stamp new file mode 100644 index 0000000..6fb3fe7 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/stamps/nameConfig.cmake.in.stamp @@ -0,0 +1,42 @@ +# generated from ament/cmake/core/templates/nameConfig.cmake.in + +# prevent multiple inclusion +if(_@PROJECT_NAME@_CONFIG_INCLUDED) + # ensure to keep the found flag the same + if(NOT DEFINED @PROJECT_NAME@_FOUND) + # explicitly set it to FALSE, otherwise CMake will set it to TRUE + set(@PROJECT_NAME@_FOUND FALSE) + elseif(NOT @PROJECT_NAME@_FOUND) + # use separate condition to avoid uninitialized variable warning + set(@PROJECT_NAME@_FOUND FALSE) + endif() + return() +endif() +set(_@PROJECT_NAME@_CONFIG_INCLUDED TRUE) + +# output package information +if(NOT @PROJECT_NAME@_FIND_QUIETLY) + message(STATUS "Found @PROJECT_NAME@: @PACKAGE_VERSION@ (${@PROJECT_NAME@_DIR})") +endif() + +# warn when using a deprecated package +if(NOT "@PACKAGE_DEPRECATED@" STREQUAL "") + set(_msg "Package '@PROJECT_NAME@' is deprecated") + # append custom deprecation text if available + if(NOT "@PACKAGE_DEPRECATED@" STREQUAL "TRUE") + set(_msg "${_msg} (@PACKAGE_DEPRECATED@)") + endif() + # optionally quiet the deprecation message + if(NOT ${@PROJECT_NAME@_DEPRECATED_QUIET}) + message(DEPRECATION "${_msg}") + endif() +endif() + +# flag package as ament-based to distinguish it after being find_package()-ed +set(@PROJECT_NAME@_FOUND_AMENT_PACKAGE TRUE) + +# include all config extra files +set(_extras "@PACKAGE_CONFIG_EXTRA_FILES@") +foreach(_extra ${_extras}) + include("${@PROJECT_NAME@_DIR}/${_extra}") +endforeach() diff --git a/rm_arm_control/build/ament_cmake_core/stamps/package.xml.stamp b/rm_arm_control/build/ament_cmake_core/stamps/package.xml.stamp new file mode 100644 index 0000000..9585814 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/stamps/package.xml.stamp @@ -0,0 +1,19 @@ + + + + rm_arm_control + 1.0.0 + rm_arm_control package + Your Name + Apache-2.0 + + ament_cmake + rclcpp + geometry_msgs + nav_msgs + ros2launch + + + ament_cmake + + diff --git a/rm_arm_control/build/ament_cmake_core/stamps/package_xml_2_cmake.py.stamp b/rm_arm_control/build/ament_cmake_core/stamps/package_xml_2_cmake.py.stamp new file mode 100644 index 0000000..8be9894 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/stamps/package_xml_2_cmake.py.stamp @@ -0,0 +1,150 @@ +#!/usr/bin/env python3 + +# Copyright 2014-2015 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 argparse +from collections import OrderedDict +import os +import sys + +from catkin_pkg.package import parse_package_string + + +def main(argv=sys.argv[1:]): + """ + Extract the information from package.xml and make them accessible to CMake. + + Parse the given package.xml file and + print CMake code defining several variables containing the content. + """ + parser = argparse.ArgumentParser( + description='Parse package.xml file and print CMake code defining ' + 'several variables', + ) + parser.add_argument( + 'package_xml', + type=argparse.FileType('r', encoding='utf-8'), + help='The path to a package.xml file', + ) + parser.add_argument( + 'outfile', + nargs='?', + help='The filename where the output should be written to', + ) + args = parser.parse_args(argv) + + try: + package = parse_package_string( + args.package_xml.read(), filename=args.package_xml.name) + except Exception as e: + print("Error parsing '%s':" % args.package_xml.name, file=sys.stderr) + raise e + finally: + args.package_xml.close() + + lines = generate_cmake_code(package) + if args.outfile: + with open(args.outfile, 'w', encoding='utf-8') as f: + for line in lines: + f.write('%s\n' % line) + else: + for line in lines: + print(line) + + +def get_dependency_values(key, depends): + dependencies = [] + + # Filter the dependencies, checking for any condition attributes + dependencies.append((key, ' '.join([ + '"%s"' % str(d) for d in depends + if d.condition is None or d.evaluate_condition(os.environ) + ]))) + + for d in depends: + comparisons = [ + 'version_lt', + 'version_lte', + 'version_eq', + 'version_gte', + 'version_gt'] + for comp in comparisons: + value = getattr(d, comp, None) + if value is not None: + dependencies.append(('%s_%s_%s' % (key, str(d), comp.upper()), + '"%s"' % value)) + return dependencies + + +def generate_cmake_code(package): + """ + Return a list of CMake set() commands containing the manifest information. + + :param package: catkin_pkg.package.Package + :returns: list of str + """ + variables = [] + variables.append(('VERSION', '"%s"' % package.version)) + + variables.append(( + 'MAINTAINER', + '"%s"' % (', '.join([str(m) for m in package.maintainers])))) + + variables.extend(get_dependency_values('BUILD_DEPENDS', + package.build_depends)) + variables.extend(get_dependency_values('BUILDTOOL_DEPENDS', + package.buildtool_depends)) + variables.extend(get_dependency_values('BUILD_EXPORT_DEPENDS', + package.build_export_depends)) + variables.extend(get_dependency_values('BUILDTOOL_EXPORT_DEPENDS', + package.buildtool_export_depends)) + variables.extend(get_dependency_values('EXEC_DEPENDS', + package.exec_depends)) + variables.extend(get_dependency_values('TEST_DEPENDS', + package.test_depends)) + variables.extend(get_dependency_values('GROUP_DEPENDS', + package.group_depends)) + variables.extend(get_dependency_values('MEMBER_OF_GROUPS', + package.member_of_groups)) + + deprecated = [e.content for e in package.exports + if e.tagname == 'deprecated'] + variables.append(('DEPRECATED', + '"%s"' % ((deprecated[0] if deprecated[0] else 'TRUE') + if deprecated + else ''))) + + lines = [] + lines.append('set(_AMENT_PACKAGE_NAME "%s")' % package.name) + for (k, v) in variables: + lines.append('set(%s_%s %s)' % (package.name, k, v)) + + lines.append('set(%s_EXPORT_TAGS)' % package.name) + replaces = OrderedDict() + replaces['${prefix}/'] = '' + replaces['\\'] = '\\\\' # escape backslashes + replaces['"'] = '\\"' # prevent double quotes to end the CMake string + replaces[';'] = '\\;' # prevent semicolons to be interpreted as list separators + for export in package.exports: + export = str(export) + for k, v in replaces.items(): + export = export.replace(k, v) + lines.append('list(APPEND %s_EXPORT_TAGS "%s")' % (package.name, export)) + + return lines + + +if __name__ == '__main__': + main() diff --git a/rm_arm_control/build/ament_cmake_core/stamps/path.sh.stamp b/rm_arm_control/build/ament_cmake_core/stamps/path.sh.stamp new file mode 100644 index 0000000..e59b749 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/stamps/path.sh.stamp @@ -0,0 +1,5 @@ +# copied from ament_cmake_core/cmake/environment_hooks/environment/path.sh + +if [ -d "$AMENT_CURRENT_PREFIX/bin" ]; then + ament_prepend_unique_value PATH "$AMENT_CURRENT_PREFIX/bin" +fi diff --git a/rm_arm_control/build/ament_cmake_core/stamps/templates_2_cmake.py.stamp b/rm_arm_control/build/ament_cmake_core/stamps/templates_2_cmake.py.stamp new file mode 100644 index 0000000..fb2fb47 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_core/stamps/templates_2_cmake.py.stamp @@ -0,0 +1,112 @@ +#!/usr/bin/env python3 + +# Copyright 2014-2015 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 argparse +import os +import sys + +from ament_package.templates import get_environment_hook_template_path +from ament_package.templates import get_package_level_template_names +from ament_package.templates import get_package_level_template_path +from ament_package.templates import get_prefix_level_template_names +from ament_package.templates import get_prefix_level_template_path + +IS_WINDOWS = os.name == 'nt' + + +def main(argv=sys.argv[1:]): + """ + Extract the information about templates provided by ament_package. + + Call the API provided by ament_package and + print CMake code defining several variables containing information about + the available templates. + """ + parser = argparse.ArgumentParser( + description='Extract information about templates provided by ' + 'ament_package and print CMake code defining several ' + 'variables', + ) + parser.add_argument( + 'outfile', + nargs='?', + help='The filename where the output should be written to', + ) + args = parser.parse_args(argv) + + lines = generate_cmake_code() + if args.outfile: + basepath = os.path.dirname(args.outfile) + if not os.path.exists(basepath): + os.makedirs(basepath) + with open(args.outfile, 'w') as f: + for line in lines: + f.write('%s\n' % line) + else: + for line in lines: + print(line) + + +def generate_cmake_code(): + """ + Return a list of CMake set() commands containing the template information. + + :returns: list of str + """ + variables = [] + + if not IS_WINDOWS: + variables.append(( + 'ENVIRONMENT_HOOK_LIBRARY_PATH', + '"%s"' % get_environment_hook_template_path('library_path.sh'))) + else: + variables.append(('ENVIRONMENT_HOOK_LIBRARY_PATH', '')) + + ext = '.bat.in' if IS_WINDOWS else '.sh.in' + variables.append(( + 'ENVIRONMENT_HOOK_PYTHONPATH', + '"%s"' % get_environment_hook_template_path('pythonpath' + ext))) + + templates = [] + for name in get_package_level_template_names(): + templates.append('"%s"' % get_package_level_template_path(name)) + variables.append(( + 'PACKAGE_LEVEL', + templates)) + + templates = [] + for name in get_prefix_level_template_names(): + templates.append('"%s"' % get_prefix_level_template_path(name)) + variables.append(( + 'PREFIX_LEVEL', + templates)) + + lines = [] + for (k, v) in variables: + if isinstance(v, list): + lines.append('set(ament_cmake_package_templates_%s "")' % k) + for vv in v: + lines.append('list(APPEND ament_cmake_package_templates_%s %s)' + % (k, vv)) + else: + lines.append('set(ament_cmake_package_templates_%s %s)' % (k, v)) + # Ensure backslashes are replaced with forward slashes because CMake cannot + # parse files with backslashes in it. + return [line.replace('\\', '/') for line in lines] + + +if __name__ == '__main__': + main() diff --git a/rm_arm_control/build/ament_cmake_environment_hooks/ament_prefix_path.dsv b/rm_arm_control/build/ament_cmake_environment_hooks/ament_prefix_path.dsv new file mode 100644 index 0000000..79d4c95 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_environment_hooks/ament_prefix_path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate;AMENT_PREFIX_PATH; diff --git a/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.bash b/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.bash new file mode 100644 index 0000000..49782f2 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.bash @@ -0,0 +1,46 @@ +# generated from ament_package/template/package_level/local_setup.bash.in + +# source local_setup.sh from same directory as this file +_this_path=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" && pwd) +# provide AMENT_CURRENT_PREFIX to shell script +AMENT_CURRENT_PREFIX=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." && pwd) +# store AMENT_CURRENT_PREFIX to restore it before each environment hook +_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX + +# trace output +if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_this_path/local_setup.sh\"" +fi +. "$_this_path/local_setup.sh" +unset _this_path + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks +AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX +# list all environment hooks of this package + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + # restore AMENT_CURRENT_PREFIX for each environment hook + AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + . "$_hook" + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +unset _package_local_setup_AMENT_CURRENT_PREFIX +unset AMENT_CURRENT_PREFIX diff --git a/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.dsv b/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.dsv new file mode 100644 index 0000000..e6b4f20 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.dsv @@ -0,0 +1,2 @@ +source;share/rm_arm_control/environment/ament_prefix_path.sh +source;share/rm_arm_control/environment/path.sh diff --git a/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.sh b/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.sh new file mode 100644 index 0000000..db48139 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.sh @@ -0,0 +1,184 @@ +# generated from ament_package/template/package_level/local_setup.sh.in + +# since this file is sourced use either the provided AMENT_CURRENT_PREFIX +# or fall back to the destination set at configure time +: ${AMENT_CURRENT_PREFIX:="/usr/local"} +if [ ! -d "$AMENT_CURRENT_PREFIX" ]; then + if [ -z "$COLCON_CURRENT_PREFIX" ]; then + echo "The compile time prefix path '$AMENT_CURRENT_PREFIX' doesn't " \ + "exist. Consider sourcing a different extension than '.sh'." 1>&2 + else + AMENT_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX" + fi +fi + +# function to append values to environment variables +# using colons as separators and avoiding leading separators +ament_append_value() { + # arguments + _listname="$1" + _value="$2" + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # avoid leading separator + eval _values=\"\$$_listname\" + if [ -z "$_values" ]; then + eval export $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + _ament_append_value_IFS=$IFS + unset IFS + eval export $_listname=\"\$$_listname:$_value\" + #eval echo "append list \$$_listname" + IFS=$_ament_append_value_IFS + unset _ament_append_value_IFS + fi + unset _values + + unset _value + unset _listname +} + +# function to append non-duplicate values to environment variables +# using colons as separators and avoiding leading separators +ament_append_unique_value() { + # arguments + _listname=$1 + _value=$2 + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # check if the list contains the value + eval _values=\$$_listname + _duplicate= + _ament_append_unique_value_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array _values + fi + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + if [ $_item = $_value ]; then + _duplicate=1 + fi + done + unset _item + + # append only non-duplicates + if [ -z "$_duplicate" ]; then + # avoid leading separator + if [ -z "$_values" ]; then + eval $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + unset IFS + eval $_listname=\"\$$_listname:$_value\" + #eval echo "append list \$$_listname" + fi + fi + IFS=$_ament_append_unique_value_IFS + unset _ament_append_unique_value_IFS + unset _duplicate + unset _values + + unset _value + unset _listname +} + +# function to prepend non-duplicate values to environment variables +# using colons as separators and avoiding trailing separators +ament_prepend_unique_value() { + # arguments + _listname="$1" + _value="$2" + #echo "listname $_listname" + #eval echo "list value \$$_listname" + #echo "value $_value" + + # check if the list contains the value + eval _values=\"\$$_listname\" + _duplicate= + _ament_prepend_unique_value_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array _values + fi + for _item in $_values; do + # ignore empty strings + if [ -z "$_item" ]; then + continue + fi + if [ "$_item" = "$_value" ]; then + _duplicate=1 + fi + done + unset _item + + # prepend only non-duplicates + if [ -z "$_duplicate" ]; then + # avoid trailing separator + if [ -z "$_values" ]; then + eval export $_listname=\"$_value\" + #eval echo "set list \$$_listname" + else + # field separator must not be a colon + unset IFS + eval export $_listname=\"$_value:\$$_listname\" + #eval echo "prepend list \$$_listname" + fi + fi + IFS=$_ament_prepend_unique_value_IFS + unset _ament_prepend_unique_value_IFS + unset _duplicate + unset _values + + unset _value + unset _listname +} + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# list all environment hooks of this package +ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/rm_arm_control/environment/ament_prefix_path.sh" +ament_append_value AMENT_ENVIRONMENT_HOOKS "$AMENT_CURRENT_PREFIX/share/rm_arm_control/environment/path.sh" + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + if [ "$AMENT_SHELL" = "zsh" ]; then + ament_zsh_to_array AMENT_ENVIRONMENT_HOOKS + fi + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + if [ -f "$_hook" ]; then + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + # trace output + if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_hook\"" + fi + . "$_hook" + fi + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +# reset AMENT_CURRENT_PREFIX after each package +# allowing to source multiple package-level setup files +unset AMENT_CURRENT_PREFIX diff --git a/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.zsh b/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.zsh new file mode 100644 index 0000000..fe161be --- /dev/null +++ b/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.zsh @@ -0,0 +1,59 @@ +# generated from ament_package/template/package_level/local_setup.zsh.in + +AMENT_SHELL=zsh + +# source local_setup.sh from same directory as this file +_this_path=$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd) +# provide AMENT_CURRENT_PREFIX to shell script +AMENT_CURRENT_PREFIX=$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd) +# store AMENT_CURRENT_PREFIX to restore it before each environment hook +_package_local_setup_AMENT_CURRENT_PREFIX=$AMENT_CURRENT_PREFIX + +# function to convert array-like strings into arrays +# to wordaround SH_WORD_SPLIT not being set +ament_zsh_to_array() { + local _listname=$1 + local _dollar="$" + local _split="{=" + local _to_array="(\"$_dollar$_split$_listname}\")" + eval $_listname=$_to_array +} + +# trace output +if [ -n "$AMENT_TRACE_SETUP_FILES" ]; then + echo "# . \"$_this_path/local_setup.sh\"" +fi +# the package-level local_setup file unsets AMENT_CURRENT_PREFIX +. "$_this_path/local_setup.sh" +unset _this_path + +# unset AMENT_ENVIRONMENT_HOOKS +# if not appending to them for return +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + unset AMENT_ENVIRONMENT_HOOKS +fi + +# restore AMENT_CURRENT_PREFIX before evaluating the environment hooks +AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX +# list all environment hooks of this package + +# source all shell-specific environment hooks of this package +# if not returning them +if [ -z "$AMENT_RETURN_ENVIRONMENT_HOOKS" ]; then + _package_local_setup_IFS=$IFS + IFS=":" + for _hook in $AMENT_ENVIRONMENT_HOOKS; do + # restore AMENT_CURRENT_PREFIX for each environment hook + AMENT_CURRENT_PREFIX=$_package_local_setup_AMENT_CURRENT_PREFIX + # restore IFS before sourcing other files + IFS=$_package_local_setup_IFS + . "$_hook" + done + unset _hook + IFS=$_package_local_setup_IFS + unset _package_local_setup_IFS + unset AMENT_ENVIRONMENT_HOOKS +fi + +unset _package_local_setup_AMENT_CURRENT_PREFIX +unset AMENT_CURRENT_PREFIX diff --git a/rm_arm_control/build/ament_cmake_environment_hooks/package.dsv b/rm_arm_control/build/ament_cmake_environment_hooks/package.dsv new file mode 100644 index 0000000..44be3e1 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_environment_hooks/package.dsv @@ -0,0 +1,4 @@ +source;share/rm_arm_control/local_setup.bash +source;share/rm_arm_control/local_setup.dsv +source;share/rm_arm_control/local_setup.sh +source;share/rm_arm_control/local_setup.zsh diff --git a/rm_arm_control/build/ament_cmake_environment_hooks/path.dsv b/rm_arm_control/build/ament_cmake_environment_hooks/path.dsv new file mode 100644 index 0000000..b94426a --- /dev/null +++ b/rm_arm_control/build/ament_cmake_environment_hooks/path.dsv @@ -0,0 +1 @@ +prepend-non-duplicate-if-exists;PATH;bin diff --git a/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/package_run_dependencies/rm_arm_control b/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/package_run_dependencies/rm_arm_control new file mode 100644 index 0000000..0e2b891 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/package_run_dependencies/rm_arm_control @@ -0,0 +1 @@ +rclcpp;geometry_msgs;nav_msgs;ros2launch \ No newline at end of file diff --git a/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/packages/rm_arm_control b/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/packages/rm_arm_control new file mode 100644 index 0000000..e69de29 diff --git a/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/parent_prefix_path/rm_arm_control b/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/parent_prefix_path/rm_arm_control new file mode 100644 index 0000000..ad320a3 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/parent_prefix_path/rm_arm_control @@ -0,0 +1 @@ +/home/zj/hivecore_robot_os/HiveCoreR1/install/arm_keyboard_input:/home/zj/hivecore_robot_os/HiveCoreR1/install/robot_bringup:/home/zj/hivecore_robot_os/HiveCoreR1/install/rm_arm_control:/opt/ros/humble \ No newline at end of file diff --git a/rm_arm_control/build/ament_cmake_package_templates/templates.cmake b/rm_arm_control/build/ament_cmake_package_templates/templates.cmake new file mode 100644 index 0000000..42a5a03 --- /dev/null +++ b/rm_arm_control/build/ament_cmake_package_templates/templates.cmake @@ -0,0 +1,14 @@ +set(ament_cmake_package_templates_ENVIRONMENT_HOOK_LIBRARY_PATH "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/environment_hook/library_path.sh") +set(ament_cmake_package_templates_ENVIRONMENT_HOOK_PYTHONPATH "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/environment_hook/pythonpath.sh.in") +set(ament_cmake_package_templates_PACKAGE_LEVEL "") +list(APPEND ament_cmake_package_templates_PACKAGE_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/package_level/local_setup.bash.in") +list(APPEND ament_cmake_package_templates_PACKAGE_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/package_level/local_setup.sh.in") +list(APPEND ament_cmake_package_templates_PACKAGE_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/package_level/local_setup.zsh.in") +set(ament_cmake_package_templates_PREFIX_LEVEL "") +list(APPEND ament_cmake_package_templates_PREFIX_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/prefix_level/local_setup.bash") +list(APPEND ament_cmake_package_templates_PREFIX_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/prefix_level/local_setup.sh.in") +list(APPEND ament_cmake_package_templates_PREFIX_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/prefix_level/local_setup.zsh") +list(APPEND ament_cmake_package_templates_PREFIX_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/prefix_level/setup.bash") +list(APPEND ament_cmake_package_templates_PREFIX_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/prefix_level/setup.sh.in") +list(APPEND ament_cmake_package_templates_PREFIX_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/prefix_level/setup.zsh") +list(APPEND ament_cmake_package_templates_PREFIX_LEVEL "/opt/ros/humble/lib/python3.10/site-packages/ament_package/template/prefix_level/_local_setup_util.py") diff --git a/rm_arm_control/build/ament_cmake_uninstall_target/ament_cmake_uninstall_target.cmake b/rm_arm_control/build/ament_cmake_uninstall_target/ament_cmake_uninstall_target.cmake new file mode 100644 index 0000000..9909b2b --- /dev/null +++ b/rm_arm_control/build/ament_cmake_uninstall_target/ament_cmake_uninstall_target.cmake @@ -0,0 +1,57 @@ +# generated from +# ament_cmake_core/cmake/uninstall_target/ament_cmake_uninstall_target.cmake.in + +function(ament_cmake_uninstall_target_remove_empty_directories path) + set(install_space "/usr/local") + if(install_space STREQUAL "") + message(FATAL_ERROR "The CMAKE_INSTALL_PREFIX variable must not be empty") + endif() + + string(LENGTH "${install_space}" length) + string(SUBSTRING "${path}" 0 ${length} path_prefix) + if(NOT path_prefix STREQUAL install_space) + message(FATAL_ERROR "The path '${path}' must be within the install space '${install_space}'") + endif() + if(path STREQUAL install_space) + return() + endif() + + # check if directory is empty + file(GLOB files "${path}/*") + list(LENGTH files length) + if(length EQUAL 0) + message(STATUS "Uninstalling: ${path}/") + execute_process(COMMAND "/usr/bin/cmake" "-E" "remove_directory" "${path}") + # recursively try to remove parent directories + get_filename_component(parent_path "${path}" PATH) + ament_cmake_uninstall_target_remove_empty_directories("${parent_path}") + endif() +endfunction() + +# uninstall files installed using the standard install() function +set(install_manifest "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/install_manifest.txt") +if(NOT EXISTS "${install_manifest}") + message(FATAL_ERROR "Cannot find install manifest: ${install_manifest}") +endif() + +file(READ "${install_manifest}" installed_files) +string(REGEX REPLACE "\n" ";" installed_files "${installed_files}") +foreach(installed_file ${installed_files}) + if(EXISTS "${installed_file}" OR IS_SYMLINK "${installed_file}") + message(STATUS "Uninstalling: ${installed_file}") + file(REMOVE "${installed_file}") + if(EXISTS "${installed_file}" OR IS_SYMLINK "${installed_file}") + message(FATAL_ERROR "Failed to remove '${installed_file}'") + endif() + + # remove empty parent folders + get_filename_component(parent_path "${installed_file}" PATH) + ament_cmake_uninstall_target_remove_empty_directories("${parent_path}") + endif() +endforeach() + +# end of template + +message(STATUS "Execute custom uninstall script") + +# begin of custom uninstall code diff --git a/rm_arm_control/build/cmake_install.cmake b/rm_arm_control/build/cmake_install.cmake new file mode 100644 index 0000000..d4e3b19 --- /dev/null +++ b/rm_arm_control/build/cmake_install.cmake @@ -0,0 +1,137 @@ +# Install script for directory: /home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control + +# Set the install prefix +if(NOT DEFINED CMAKE_INSTALL_PREFIX) + set(CMAKE_INSTALL_PREFIX "/usr/local") +endif() +string(REGEX REPLACE "/$" "" CMAKE_INSTALL_PREFIX "${CMAKE_INSTALL_PREFIX}") + +# Set the install configuration name. +if(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME) + if(BUILD_TYPE) + string(REGEX REPLACE "^[^A-Za-z0-9_]+" "" + CMAKE_INSTALL_CONFIG_NAME "${BUILD_TYPE}") + else() + set(CMAKE_INSTALL_CONFIG_NAME "") + endif() + message(STATUS "Install configuration: \"${CMAKE_INSTALL_CONFIG_NAME}\"") +endif() + +# Set the component getting installed. +if(NOT CMAKE_INSTALL_COMPONENT) + if(COMPONENT) + message(STATUS "Install component: \"${COMPONENT}\"") + set(CMAKE_INSTALL_COMPONENT "${COMPONENT}") + else() + set(CMAKE_INSTALL_COMPONENT) + endif() +endif() + +# Install shared libraries without execute permission? +if(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE) + set(CMAKE_INSTALL_SO_NO_EXE "1") +endif() + +# Is this installation the result of a crosscompile? +if(NOT DEFINED CMAKE_CROSSCOMPILING) + set(CMAKE_CROSSCOMPILING "FALSE") +endif() + +# Set default install directory permissions. +if(NOT DEFINED CMAKE_OBJDUMP) + set(CMAKE_OBJDUMP "/usr/bin/objdump") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + if(EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/rm_arm_control/rm_arm_control" AND + NOT IS_SYMLINK "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/rm_arm_control/rm_arm_control") + file(RPATH_CHECK + FILE "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/rm_arm_control/rm_arm_control" + RPATH "") + endif() + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/lib/rm_arm_control" TYPE EXECUTABLE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/rm_arm_control") + if(EXISTS "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/rm_arm_control/rm_arm_control" AND + NOT IS_SYMLINK "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/rm_arm_control/rm_arm_control") + file(RPATH_CHANGE + FILE "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/rm_arm_control/rm_arm_control" + OLD_RPATH "/opt/ros/humble/lib:/home/zj/hivecore_robot_os/HiveCoreR1/lib:" + NEW_RPATH "") + if(CMAKE_INSTALL_DO_STRIP) + execute_process(COMMAND "/usr/bin/strip" "$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/lib/rm_arm_control/rm_arm_control") + endif() + endif() +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control/" TYPE DIRECTORY FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/launch") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/ament_index/resource_index/package_run_dependencies" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/package_run_dependencies/rm_arm_control") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/ament_index/resource_index/parent_prefix_path" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/parent_prefix_path/rm_arm_control") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control/environment" TYPE FILE FILES "/opt/ros/humble/share/ament_cmake_core/cmake/environment_hooks/environment/ament_prefix_path.sh") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control/environment" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_environment_hooks/ament_prefix_path.dsv") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control/environment" TYPE FILE FILES "/opt/ros/humble/share/ament_cmake_core/cmake/environment_hooks/environment/path.sh") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control/environment" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_environment_hooks/path.dsv") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.bash") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.sh") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.zsh") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_environment_hooks/local_setup.dsv") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_environment_hooks/package.dsv") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/ament_index/resource_index/packages" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_index/share/ament_index/resource_index/packages/rm_arm_control") +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control/cmake" TYPE FILE FILES + "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_core/rm_arm_controlConfig.cmake" + "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/ament_cmake_core/rm_arm_controlConfig-version.cmake" + ) +endif() + +if("x${CMAKE_INSTALL_COMPONENT}x" STREQUAL "xUnspecifiedx" OR NOT CMAKE_INSTALL_COMPONENT) + file(INSTALL DESTINATION "${CMAKE_INSTALL_PREFIX}/share/rm_arm_control" TYPE FILE FILES "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/package.xml") +endif() + +if(CMAKE_INSTALL_COMPONENT) + set(CMAKE_INSTALL_MANIFEST "install_manifest_${CMAKE_INSTALL_COMPONENT}.txt") +else() + set(CMAKE_INSTALL_MANIFEST "install_manifest.txt") +endif() + +string(REPLACE ";" "\n" CMAKE_INSTALL_MANIFEST_CONTENT + "${CMAKE_INSTALL_MANIFEST_FILES}") +file(WRITE "/home/zj/hivecore_robot_os/HiveCoreR1/src/rm_arm_control/build/${CMAKE_INSTALL_MANIFEST}" + "${CMAKE_INSTALL_MANIFEST_CONTENT}") diff --git a/rm_arm_control/build/libapi_cpp.so b/rm_arm_control/build/libapi_cpp.so new file mode 100644 index 0000000..aa36d5e Binary files /dev/null and b/rm_arm_control/build/libapi_cpp.so differ diff --git a/rm_arm_control/build/rm_arm_control b/rm_arm_control/build/rm_arm_control new file mode 100755 index 0000000..061d383 Binary files /dev/null and b/rm_arm_control/build/rm_arm_control differ diff --git a/rm_arm_control/data/ECO65_canfd_data.txt b/rm_arm_control/data/ECO65_canfd_data.txt new file mode 100644 index 0000000..dfd57f8 --- /dev/null +++ b/rm_arm_control/data/ECO65_canfd_data.txt @@ -0,0 +1,3600 @@ +0.049444444444444444,-0.03611111111111111,0.0375,0.049444444444444444,0.049444444444444444,0.1 +0.09888888888888889,-0.07222222222222222,0.075,0.09888888888888889,0.09888888888888889,0.2 +0.14833333333333332,-0.10833333333333332,0.11249999999999999,0.14833333333333332,0.14833333333333332,0.30000000000000004 +0.19777777777777777,-0.14444444444444443,0.15,0.19777777777777777,0.19777777777777777,0.4 +0.24722222222222223,-0.18055555555555552,0.1875,0.24722222222222223,0.24722222222222223,0.5 +0.29666666666666663,-0.21666666666666665,0.22499999999999998,0.29666666666666663,0.29666666666666663,0.6000000000000001 +0.3461111111111111,-0.25277777777777777,0.2625,0.3461111111111111,0.3461111111111111,0.7000000000000001 +0.39555555555555555,-0.28888888888888886,0.3,0.39555555555555555,0.39555555555555555,0.8 +0.445,-0.32499999999999996,0.33749999999999997,0.445,0.445,0.9 +0.49444444444444446,-0.36111111111111105,0.375,0.49444444444444446,0.49444444444444446,1.0 +0.5438888888888889,-0.3972222222222222,0.4125,0.5438888888888889,0.5438888888888889,1.1 +0.5933333333333333,-0.4333333333333333,0.44999999999999996,0.5933333333333333,0.5933333333333333,1.2000000000000002 +0.6427777777777778,-0.4694444444444444,0.4875,0.6427777777777778,0.6427777777777778,1.3 +0.6922222222222222,-0.5055555555555555,0.525,0.6922222222222222,0.6922222222222222,1.4000000000000001 +0.7416666666666667,-0.5416666666666666,0.5625,0.7416666666666667,0.7416666666666667,1.5 +0.7911111111111111,-0.5777777777777777,0.6,0.7911111111111111,0.7911111111111111,1.6 +0.8405555555555555,-0.6138888888888888,0.6375,0.8405555555555555,0.8405555555555555,1.7000000000000002 +0.89,-0.6499999999999999,0.6749999999999999,0.89,0.89,1.8 +0.9394444444444444,-0.686111111111111,0.7125,0.9394444444444444,0.9394444444444444,1.9000000000000001 +0.9888888888888889,-0.7222222222222221,0.75,0.9888888888888889,0.9888888888888889,2.0 +1.0383333333333333,-0.7583333333333333,0.7875,1.0383333333333333,1.0383333333333333,2.1 +1.0877777777777777,-0.7944444444444444,0.825,1.0877777777777777,1.0877777777777777,2.2 +1.1372222222222221,-0.8305555555555555,0.8624999999999999,1.1372222222222221,1.1372222222222221,2.3000000000000003 +1.1866666666666665,-0.8666666666666666,0.8999999999999999,1.1866666666666665,1.1866666666666665,2.4000000000000004 +1.2361111111111112,-0.9027777777777777,0.9375,1.2361111111111112,1.2361111111111112,2.5 +1.2855555555555556,-0.9388888888888888,0.975,1.2855555555555556,1.2855555555555556,2.6 +1.335,-0.9749999999999999,1.0125,1.335,1.335,2.7 +1.3844444444444444,-1.011111111111111,1.05,1.3844444444444444,1.3844444444444444,2.8000000000000003 +1.4338888888888888,-1.047222222222222,1.0875,1.4338888888888888,1.4338888888888888,2.9000000000000004 +1.4833333333333334,-1.0833333333333333,1.125,1.4833333333333334,1.4833333333333334,3.0 +1.5327777777777778,-1.1194444444444442,1.1624999999999999,1.5327777777777778,1.5327777777777778,3.1 +1.5822222222222222,-1.1555555555555554,1.2,1.5822222222222222,1.5822222222222222,3.2 +1.6316666666666666,-1.1916666666666667,1.2375,1.6316666666666666,1.6316666666666666,3.3000000000000003 +1.681111111111111,-1.2277777777777776,1.275,1.681111111111111,1.681111111111111,3.4000000000000004 +1.7305555555555556,-1.2638888888888888,1.3125,1.7305555555555556,1.7305555555555556,3.5 +1.78,-1.2999999999999998,1.3499999999999999,1.78,1.78,3.6 +1.8294444444444444,-1.336111111111111,1.3875,1.8294444444444444,1.8294444444444444,3.7 +1.8788888888888888,-1.372222222222222,1.425,1.8788888888888888,1.8788888888888888,3.8000000000000003 +1.9283333333333332,-1.4083333333333332,1.4625,1.9283333333333332,1.9283333333333332,3.9000000000000004 +1.9777777777777779,-1.4444444444444442,1.5,1.9777777777777779,1.9777777777777779,4.0 +2.027222222222222,-1.4805555555555554,1.5374999999999999,2.027222222222222,2.027222222222222,4.1000000000000005 +2.0766666666666667,-1.5166666666666666,1.575,2.0766666666666667,2.0766666666666667,4.2 +2.1261111111111113,-1.5527777777777776,1.6125,2.1261111111111113,2.1261111111111113,4.3 +2.1755555555555555,-1.5888888888888888,1.65,2.1755555555555555,2.1755555555555555,4.4 +2.225,-1.6249999999999998,1.6875,2.225,2.225,4.5 +2.2744444444444443,-1.661111111111111,1.7249999999999999,2.2744444444444443,2.2744444444444443,4.6000000000000005 +2.323888888888889,-1.697222222222222,1.7625,2.323888888888889,2.323888888888889,4.7 +2.373333333333333,-1.7333333333333332,1.7999999999999998,2.373333333333333,2.373333333333333,4.800000000000001 +2.4227777777777777,-1.7694444444444444,1.8375,2.4227777777777777,2.4227777777777777,4.9 +2.4722222222222223,-1.8055555555555554,1.875,2.4722222222222223,2.4722222222222223,5.0 +2.5216666666666665,-1.8416666666666666,1.9124999999999999,2.5216666666666665,2.5216666666666665,5.1000000000000005 +2.571111111111111,-1.8777777777777775,1.95,2.571111111111111,2.571111111111111,5.2 +2.6205555555555553,-1.9138888888888888,1.9874999999999998,2.6205555555555553,2.6205555555555553,5.300000000000001 +2.67,-1.9499999999999997,2.025,2.67,2.67,5.4 +2.7194444444444446,-1.986111111111111,2.0625,2.7194444444444446,2.7194444444444446,5.5 +2.7688888888888887,-2.022222222222222,2.1,2.7688888888888887,2.7688888888888887,5.6000000000000005 +2.8183333333333334,-2.058333333333333,2.1374999999999997,2.8183333333333334,2.8183333333333334,5.7 +2.8677777777777775,-2.094444444444444,2.175,2.8677777777777775,2.8677777777777775,5.800000000000001 +2.917222222222222,-2.1305555555555555,2.2125,2.917222222222222,2.917222222222222,5.9 +2.966666666666667,-2.1666666666666665,2.25,2.966666666666667,2.966666666666667,6.0 +3.016111111111111,-2.2027777777777775,2.2875,3.016111111111111,3.016111111111111,6.1000000000000005 +3.0655555555555556,-2.2388888888888885,2.3249999999999997,3.0655555555555556,3.0655555555555556,6.2 +3.1149999999999998,-2.275,2.3625,3.1149999999999998,3.1149999999999998,6.300000000000001 +3.1644444444444444,-2.311111111111111,2.4,3.1644444444444444,3.1644444444444444,6.4 +3.213888888888889,-2.347222222222222,2.4375,3.213888888888889,3.213888888888889,6.5 +3.263333333333333,-2.3833333333333333,2.475,3.263333333333333,3.263333333333333,6.6000000000000005 +3.312777777777778,-2.4194444444444443,2.5124999999999997,3.312777777777778,3.312777777777778,6.7 +3.362222222222222,-2.4555555555555553,2.55,3.362222222222222,3.362222222222222,6.800000000000001 +3.4116666666666666,-2.4916666666666663,2.5875,3.4116666666666666,3.4116666666666666,6.9 +3.4611111111111112,-2.5277777777777777,2.625,3.4611111111111112,3.4611111111111112,7.0 +3.5105555555555554,-2.5638888888888887,2.6625,3.5105555555555554,3.5105555555555554,7.1000000000000005 +3.56,-2.5999999999999996,2.6999999999999997,3.56,3.56,7.2 +3.6094444444444442,-2.636111111111111,2.7375,3.6094444444444442,3.6094444444444442,7.300000000000001 +3.658888888888889,-2.672222222222222,2.775,3.658888888888889,3.658888888888889,7.4 +3.7083333333333335,-2.708333333333333,2.8125,3.7083333333333335,3.7083333333333335,7.5 +3.7577777777777777,-2.744444444444444,2.85,3.7577777777777777,3.7577777777777777,7.6000000000000005 +3.8072222222222223,-2.7805555555555554,2.8874999999999997,3.8072222222222223,3.8072222222222223,7.7 +3.8566666666666665,-2.8166666666666664,2.925,3.8566666666666665,3.8566666666666665,7.800000000000001 +3.906111111111111,-2.8527777777777774,2.9625,3.906111111111111,3.906111111111111,7.9 +3.9555555555555557,-2.8888888888888884,3.0,3.9555555555555557,3.9555555555555557,8.0 +4.005,-2.925,3.0375,4.005,4.005,8.1 +4.054444444444444,-2.961111111111111,3.0749999999999997,4.054444444444444,4.054444444444444,8.200000000000001 +4.103888888888889,-2.997222222222222,3.1125,4.103888888888889,4.103888888888889,8.3 +4.153333333333333,-3.033333333333333,3.15,4.153333333333333,4.153333333333333,8.4 +4.2027777777777775,-3.069444444444444,3.1875,4.2027777777777775,4.2027777777777775,8.5 +4.252222222222223,-3.105555555555555,3.225,4.252222222222223,4.252222222222223,8.6 +4.301666666666667,-3.141666666666666,3.2624999999999997,4.301666666666667,4.301666666666667,8.700000000000001 +4.351111111111111,-3.1777777777777776,3.3,4.351111111111111,4.351111111111111,8.8 +4.400555555555555,-3.2138888888888886,3.3375,4.400555555555555,4.400555555555555,8.9 +4.45,-3.2499999999999996,3.375,4.45,4.45,9.0 +4.499444444444444,-3.286111111111111,3.4125,4.499444444444444,4.499444444444444,9.1 +4.5488888888888885,-3.322222222222222,3.4499999999999997,4.5488888888888885,4.5488888888888885,9.200000000000001 +4.598333333333334,-3.358333333333333,3.4875,4.598333333333334,4.598333333333334,9.3 +4.647777777777778,-3.394444444444444,3.525,4.647777777777778,4.647777777777778,9.4 +4.697222222222222,-3.4305555555555554,3.5625,4.697222222222222,4.697222222222222,9.5 +4.746666666666666,-3.4666666666666663,3.5999999999999996,4.746666666666666,4.746666666666666,9.600000000000001 +4.796111111111111,-3.5027777777777773,3.6374999999999997,4.796111111111111,4.796111111111111,9.700000000000001 +4.845555555555555,-3.5388888888888888,3.675,4.845555555555555,4.845555555555555,9.8 +4.895,-3.5749999999999997,3.7125,4.895,4.895,9.9 +4.944444444444445,-3.6111111111111107,3.75,4.944444444444445,4.944444444444445,10.0 +4.993888888888889,-3.6472222222222217,3.7874999999999996,4.993888888888889,4.993888888888889,10.100000000000001 +5.043333333333333,-3.683333333333333,3.8249999999999997,5.043333333333333,5.043333333333333,10.200000000000001 +5.092777777777778,-3.719444444444444,3.8625,5.092777777777778,5.092777777777778,10.3 +5.142222222222222,-3.755555555555555,3.9,5.142222222222222,5.142222222222222,10.4 +5.191666666666666,-3.7916666666666665,3.9375,5.191666666666666,5.191666666666666,10.5 +5.241111111111111,-3.8277777777777775,3.9749999999999996,5.241111111111111,5.241111111111111,10.600000000000001 +5.290555555555556,-3.8638888888888885,4.0125,5.290555555555556,5.290555555555556,10.700000000000001 +5.34,-3.8999999999999995,4.05,5.34,5.34,10.8 +5.389444444444444,-3.936111111111111,4.0874999999999995,5.389444444444444,5.389444444444444,10.9 +5.438888888888889,-3.972222222222222,4.125,5.438888888888889,5.438888888888889,11.0 +5.488333333333333,-4.008333333333333,4.1625,5.488333333333333,5.488333333333333,11.100000000000001 +5.5377777777777775,-4.044444444444444,4.2,5.5377777777777775,5.5377777777777775,11.200000000000001 +5.5872222222222225,-4.080555555555555,4.2375,5.5872222222222225,5.5872222222222225,11.3 +5.636666666666667,-4.116666666666666,4.2749999999999995,5.636666666666667,5.636666666666667,11.4 +5.686111111111111,-4.152777777777778,4.3125,5.686111111111111,5.686111111111111,11.5 +5.735555555555555,-4.188888888888888,4.35,5.735555555555555,5.735555555555555,11.600000000000001 +5.785,-4.225,4.3875,5.785,5.785,11.700000000000001 +5.834444444444444,-4.261111111111111,4.425,5.834444444444444,5.834444444444444,11.8 +5.8838888888888885,-4.297222222222222,4.4624999999999995,5.8838888888888885,5.8838888888888885,11.9 +5.933333333333334,-4.333333333333333,4.5,5.933333333333334,5.933333333333334,12.0 +5.982777777777778,-4.3694444444444445,4.5375,5.982777777777778,5.982777777777778,12.100000000000001 +6.032222222222222,-4.405555555555555,4.575,6.032222222222222,6.032222222222222,12.200000000000001 +6.081666666666667,-4.441666666666666,4.6125,6.081666666666667,6.081666666666667,12.3 +6.131111111111111,-4.477777777777777,4.6499999999999995,6.131111111111111,6.131111111111111,12.4 +6.180555555555555,-4.513888888888888,4.6875,6.180555555555555,6.180555555555555,12.5 +6.2299999999999995,-4.55,4.725,6.2299999999999995,6.2299999999999995,12.600000000000001 +6.279444444444445,-4.58611111111111,4.7625,6.279444444444445,6.279444444444445,12.700000000000001 +6.328888888888889,-4.622222222222222,4.8,6.328888888888889,6.328888888888889,12.8 +6.378333333333333,-4.658333333333333,4.8374999999999995,6.378333333333333,6.378333333333333,12.9 +6.427777777777778,-4.694444444444444,4.875,6.427777777777778,6.427777777777778,13.0 +6.477222222222222,-4.730555555555555,4.9125,6.477222222222222,6.477222222222222,13.100000000000001 +6.526666666666666,-4.766666666666667,4.95,6.526666666666666,6.526666666666666,13.200000000000001 +6.576111111111111,-4.802777777777777,4.9875,6.576111111111111,6.576111111111111,13.3 +6.625555555555556,-4.838888888888889,5.0249999999999995,6.625555555555556,6.625555555555556,13.4 +6.675,-4.874999999999999,5.0625,6.675,6.675,13.5 +6.724444444444444,-4.9111111111111105,5.1,6.724444444444444,6.724444444444444,13.600000000000001 +6.773888888888889,-4.947222222222222,5.1375,6.773888888888889,6.773888888888889,13.700000000000001 +6.823333333333333,-4.9833333333333325,5.175,6.823333333333333,6.823333333333333,13.8 +6.872777777777777,-5.019444444444444,5.2124999999999995,6.872777777777777,6.872777777777777,13.9 +6.9222222222222225,-5.055555555555555,5.25,6.9222222222222225,6.9222222222222225,14.0 +6.971666666666667,-5.091666666666666,5.2875,6.971666666666667,6.971666666666667,14.100000000000001 +7.021111111111111,-5.127777777777777,5.325,7.021111111111111,7.021111111111111,14.200000000000001 +7.070555555555555,-5.163888888888889,5.3625,7.070555555555555,7.070555555555555,14.3 +7.12,-5.199999999999999,5.3999999999999995,7.12,7.12,14.4 +7.169444444444444,-5.236111111111111,5.4375,7.169444444444444,7.169444444444444,14.5 +7.2188888888888885,-5.272222222222222,5.475,7.2188888888888885,7.2188888888888885,14.600000000000001 +7.2683333333333335,-5.308333333333333,5.5125,7.2683333333333335,7.2683333333333335,14.700000000000001 +7.317777777777778,-5.344444444444444,5.55,7.317777777777778,7.317777777777778,14.8 +7.367222222222222,-5.380555555555555,5.5874999999999995,7.367222222222222,7.367222222222222,14.9 +7.416666666666667,-5.416666666666666,5.625,7.416666666666667,7.416666666666667,15.0 +7.466111111111111,-5.4527777777777775,5.6625,7.466111111111111,7.466111111111111,15.100000000000001 +7.515555555555555,-5.488888888888888,5.7,7.515555555555555,7.515555555555555,15.200000000000001 +7.5649999999999995,-5.5249999999999995,5.7375,7.5649999999999995,7.5649999999999995,15.3 +7.614444444444445,-5.561111111111111,5.7749999999999995,7.614444444444445,7.614444444444445,15.4 +7.663888888888889,-5.597222222222221,5.8125,7.663888888888889,7.663888888888889,15.5 +7.713333333333333,-5.633333333333333,5.85,7.713333333333333,7.713333333333333,15.600000000000001 +7.762777777777778,-5.669444444444444,5.8875,7.762777777777778,7.762777777777778,15.700000000000001 +7.812222222222222,-5.705555555555555,5.925,7.812222222222222,7.812222222222222,15.8 +7.861666666666666,-5.741666666666666,5.9624999999999995,7.861666666666666,7.861666666666666,15.9 +7.911111111111111,-5.777777777777777,6.0,7.911111111111111,7.911111111111111,16.0 +7.960555555555556,-5.813888888888888,6.0375,7.960555555555556,7.960555555555556,16.1 +8.01,-5.85,6.075,8.01,8.01,16.2 +8.059444444444445,-5.88611111111111,6.1125,8.059444444444445,8.059444444444445,16.3 +8.108888888888888,-5.922222222222222,6.1499999999999995,8.108888888888888,8.108888888888888,16.400000000000002 +8.158333333333333,-5.958333333333333,6.1875,8.158333333333333,8.158333333333333,16.5 +8.207777777777778,-5.994444444444444,6.225,8.207777777777778,8.207777777777778,16.6 +8.257222222222222,-6.030555555555555,6.2625,8.257222222222222,8.257222222222222,16.7 +8.306666666666667,-6.066666666666666,6.3,8.306666666666667,8.306666666666667,16.8 +8.356111111111112,-6.102777777777777,6.3374999999999995,8.356111111111112,8.356111111111112,16.900000000000002 +8.405555555555555,-6.138888888888888,6.375,8.405555555555555,8.405555555555555,17.0 +8.455,-6.175,6.4125,8.455,8.455,17.1 +8.504444444444445,-6.21111111111111,6.45,8.504444444444445,8.504444444444445,17.2 +8.553888888888888,-6.247222222222222,6.4875,8.553888888888888,8.553888888888888,17.3 +8.603333333333333,-6.283333333333332,6.5249999999999995,8.603333333333333,8.603333333333333,17.400000000000002 +8.652777777777777,-6.319444444444444,6.5625,8.652777777777777,8.652777777777777,17.5 +8.702222222222222,-6.355555555555555,6.6,8.702222222222222,8.702222222222222,17.6 +8.751666666666667,-6.391666666666666,6.6375,8.751666666666667,8.751666666666667,17.7 +8.80111111111111,-6.427777777777777,6.675,8.80111111111111,8.80111111111111,17.8 +8.850555555555555,-6.463888888888889,6.7124999999999995,8.850555555555555,8.850555555555555,17.900000000000002 +8.9,-6.499999999999999,6.75,8.9,8.9,18.0 +8.949444444444444,-6.5361111111111105,6.7875,8.949444444444444,8.949444444444444,18.1 +8.998888888888889,-6.572222222222222,6.825,8.998888888888889,8.998888888888889,18.2 +9.048333333333334,-6.6083333333333325,6.8625,9.048333333333334,9.048333333333334,18.3 +9.097777777777777,-6.644444444444444,6.8999999999999995,9.097777777777777,9.097777777777777,18.400000000000002 +9.147222222222222,-6.680555555555555,6.9375,9.147222222222222,9.147222222222222,18.5 +9.196666666666667,-6.716666666666666,6.975,9.196666666666667,9.196666666666667,18.6 +9.24611111111111,-6.752777777777777,7.0125,9.24611111111111,9.24611111111111,18.7 +9.295555555555556,-6.788888888888888,7.05,9.295555555555556,9.295555555555556,18.8 +9.345,-6.824999999999999,7.0874999999999995,9.345,9.345,18.900000000000002 +9.394444444444444,-6.861111111111111,7.125,9.394444444444444,9.394444444444444,19.0 +9.443888888888889,-6.897222222222221,7.1625,9.443888888888889,9.443888888888889,19.1 +9.493333333333332,-6.933333333333333,7.199999999999999,9.493333333333332,9.493333333333332,19.200000000000003 +9.542777777777777,-6.969444444444444,7.2375,9.542777777777777,9.542777777777777,19.3 +9.592222222222222,-7.005555555555555,7.2749999999999995,9.592222222222222,9.592222222222222,19.400000000000002 +9.641666666666666,-7.041666666666666,7.3125,9.641666666666666,9.641666666666666,19.5 +9.69111111111111,-7.0777777777777775,7.35,9.69111111111111,9.69111111111111,19.6 +9.740555555555556,-7.113888888888888,7.387499999999999,9.740555555555556,9.740555555555556,19.700000000000003 +9.79,-7.1499999999999995,7.425,9.79,9.79,19.8 +9.839444444444444,-7.18611111111111,7.4624999999999995,9.839444444444444,9.839444444444444,19.900000000000002 +9.88888888888889,-7.222222222222221,7.5,9.88888888888889,9.88888888888889,20.0 +9.938333333333333,-7.258333333333333,7.5375,9.938333333333333,9.938333333333333,20.1 +9.987777777777778,-7.294444444444443,7.574999999999999,9.987777777777778,9.987777777777778,20.200000000000003 +10.037222222222223,-7.330555555555555,7.6125,10.037222222222223,10.037222222222223,20.3 +10.086666666666666,-7.366666666666666,7.6499999999999995,10.086666666666666,10.086666666666666,20.400000000000002 +10.136111111111111,-7.402777777777777,7.6875,10.136111111111111,10.136111111111111,20.5 +10.185555555555556,-7.438888888888888,7.725,10.185555555555556,10.185555555555556,20.6 +10.235,-7.475,7.762499999999999,10.235,10.235,20.700000000000003 +10.284444444444444,-7.51111111111111,7.8,10.284444444444444,10.284444444444444,20.8 +10.33388888888889,-7.547222222222222,7.8374999999999995,10.33388888888889,10.33388888888889,20.900000000000002 +10.383333333333333,-7.583333333333333,7.875,10.383333333333333,10.383333333333333,21.0 +10.432777777777778,-7.619444444444444,7.9125,10.432777777777778,10.432777777777778,21.1 +10.482222222222221,-7.655555555555555,7.949999999999999,10.482222222222221,10.482222222222221,21.200000000000003 +10.531666666666666,-7.6916666666666655,7.9875,10.531666666666666,10.531666666666666,21.3 +10.581111111111111,-7.727777777777777,8.025,10.581111111111111,10.581111111111111,21.400000000000002 +10.630555555555555,-7.763888888888888,8.0625,10.630555555555555,10.630555555555555,21.5 +10.68,-7.799999999999999,8.1,10.68,10.68,21.6 +10.729444444444445,-7.83611111111111,8.1375,10.729444444444445,10.729444444444445,21.700000000000003 +10.778888888888888,-7.872222222222222,8.174999999999999,10.778888888888888,10.778888888888888,21.8 +10.828333333333333,-7.908333333333332,8.2125,10.828333333333333,10.828333333333333,21.900000000000002 +10.877777777777778,-7.944444444444444,8.25,10.877777777777778,10.877777777777778,22.0 +10.927222222222222,-7.980555555555555,8.2875,10.927222222222222,10.927222222222222,22.1 +10.976666666666667,-8.016666666666666,8.325,10.976666666666667,10.976666666666667,22.200000000000003 +11.026111111111112,-8.052777777777777,8.362499999999999,11.026111111111112,11.026111111111112,22.3 +11.075555555555555,-8.088888888888889,8.4,11.075555555555555,11.075555555555555,22.400000000000002 +11.125,-8.125,8.4375,11.125,11.125,22.5 +11.174444444444445,-8.16111111111111,8.475,11.174444444444445,11.174444444444445,22.6 +11.223888888888888,-8.197222222222221,8.5125,11.223888888888888,11.223888888888888,22.700000000000003 +11.273333333333333,-8.233333333333333,8.549999999999999,11.273333333333333,11.273333333333333,22.8 +11.322777777777777,-8.269444444444444,8.5875,11.322777777777777,11.322777777777777,22.900000000000002 +11.372222222222222,-8.305555555555555,8.625,11.372222222222222,11.372222222222222,23.0 +11.421666666666667,-8.341666666666665,8.6625,11.421666666666667,11.421666666666667,23.1 +11.47111111111111,-8.377777777777776,8.7,11.47111111111111,11.47111111111111,23.200000000000003 +11.520555555555555,-8.413888888888888,8.737499999999999,11.520555555555555,11.520555555555555,23.3 +11.57,-8.45,8.775,11.57,11.57,23.400000000000002 +11.619444444444444,-8.48611111111111,8.8125,11.619444444444444,11.619444444444444,23.5 +11.668888888888889,-8.522222222222222,8.85,11.668888888888889,11.668888888888889,23.6 +11.718333333333334,-8.558333333333332,8.8875,11.718333333333334,11.718333333333334,23.700000000000003 +11.767777777777777,-8.594444444444443,8.924999999999999,11.767777777777777,11.767777777777777,23.8 +11.817222222222222,-8.630555555555555,8.9625,11.817222222222222,11.817222222222222,23.900000000000002 +11.866666666666667,-8.666666666666666,9.0,11.866666666666667,11.866666666666667,24.0 +11.91611111111111,-8.702777777777778,9.0375,11.91611111111111,11.91611111111111,24.1 +11.965555555555556,-8.738888888888889,9.075,11.965555555555556,11.965555555555556,24.200000000000003 +12.015,-8.774999999999999,9.112499999999999,12.015,12.015,24.3 +12.064444444444444,-8.81111111111111,9.15,12.064444444444444,12.064444444444444,24.400000000000002 +12.113888888888889,-8.847222222222221,9.1875,12.113888888888889,12.113888888888889,24.5 +12.163333333333334,-8.883333333333333,9.225,12.163333333333334,12.163333333333334,24.6 +12.212777777777777,-8.919444444444444,9.2625,12.212777777777777,12.212777777777777,24.700000000000003 +12.262222222222222,-8.955555555555554,9.299999999999999,12.262222222222222,12.262222222222222,24.8 +12.311666666666666,-8.991666666666665,9.3375,12.311666666666666,12.311666666666666,24.900000000000002 +12.36111111111111,-9.027777777777777,9.375,12.36111111111111,12.36111111111111,25.0 +12.410555555555556,-9.063888888888888,9.4125,12.410555555555556,12.410555555555556,25.1 +12.459999999999999,-9.1,9.45,12.459999999999999,12.459999999999999,25.200000000000003 +12.509444444444444,-9.136111111111111,9.487499999999999,12.509444444444444,12.509444444444444,25.3 +12.55888888888889,-9.17222222222222,9.525,12.55888888888889,12.55888888888889,25.400000000000002 +12.608333333333333,-9.208333333333332,9.5625,12.608333333333333,12.608333333333333,25.5 +12.657777777777778,-9.244444444444444,9.6,12.657777777777778,12.657777777777778,25.6 +12.707222222222223,-9.280555555555555,9.6375,12.707222222222223,12.707222222222223,25.700000000000003 +12.756666666666666,-9.316666666666666,9.674999999999999,12.756666666666666,12.756666666666666,25.8 +12.806111111111111,-9.352777777777776,9.7125,12.806111111111111,12.806111111111111,25.900000000000002 +12.855555555555556,-9.388888888888888,9.75,12.855555555555556,12.855555555555556,26.0 +12.905,-9.424999999999999,9.7875,12.905,12.905,26.1 +12.954444444444444,-9.46111111111111,9.825,12.954444444444444,12.954444444444444,26.200000000000003 +13.00388888888889,-9.497222222222222,9.862499999999999,13.00388888888889,13.00388888888889,26.3 +13.053333333333333,-9.533333333333333,9.9,13.053333333333333,13.053333333333333,26.400000000000002 +13.102777777777778,-9.569444444444443,9.9375,13.102777777777778,13.102777777777778,26.5 +13.152222222222221,-9.605555555555554,9.975,13.152222222222221,13.152222222222221,26.6 +13.201666666666666,-9.641666666666666,10.0125,13.201666666666666,13.201666666666666,26.700000000000003 +13.251111111111111,-9.677777777777777,10.049999999999999,13.251111111111111,13.251111111111111,26.8 +13.300555555555555,-9.713888888888889,10.0875,13.300555555555555,13.300555555555555,26.900000000000002 +13.35,-9.749999999999998,10.125,13.35,13.35,27.0 +13.399444444444445,-9.78611111111111,10.1625,13.399444444444445,13.399444444444445,27.1 +13.448888888888888,-9.822222222222221,10.2,13.448888888888888,13.448888888888888,27.200000000000003 +13.498333333333333,-9.858333333333333,10.237499999999999,13.498333333333333,13.498333333333333,27.3 +13.547777777777778,-9.894444444444444,10.275,13.547777777777778,13.547777777777778,27.400000000000002 +13.597222222222221,-9.930555555555555,10.3125,13.597222222222221,13.597222222222221,27.5 +13.646666666666667,-9.966666666666665,10.35,13.646666666666667,13.646666666666667,27.6 +13.696111111111112,-10.002777777777776,10.3875,13.696111111111112,13.696111111111112,27.700000000000003 +13.745555555555555,-10.038888888888888,10.424999999999999,13.745555555555555,13.745555555555555,27.8 +13.795,-10.075,10.4625,13.795,13.795,27.900000000000002 +13.844444444444445,-10.11111111111111,10.5,13.844444444444445,13.844444444444445,28.0 +13.893888888888888,-10.147222222222222,10.5375,13.893888888888888,13.893888888888888,28.1 +13.943333333333333,-10.183333333333332,10.575,13.943333333333333,13.943333333333333,28.200000000000003 +13.992777777777778,-10.219444444444443,10.612499999999999,13.992777777777778,13.992777777777778,28.3 +14.042222222222222,-10.255555555555555,10.65,14.042222222222222,14.042222222222222,28.400000000000002 +14.091666666666667,-10.291666666666666,10.6875,14.091666666666667,14.091666666666667,28.5 +14.14111111111111,-10.327777777777778,10.725,14.14111111111111,14.14111111111111,28.6 +14.190555555555555,-10.363888888888887,10.7625,14.190555555555555,14.190555555555555,28.700000000000003 +14.24,-10.399999999999999,10.799999999999999,14.24,14.24,28.8 +14.289444444444444,-10.43611111111111,10.8375,14.289444444444444,14.289444444444444,28.900000000000002 +14.338888888888889,-10.472222222222221,10.875,14.338888888888889,14.338888888888889,29.0 +14.388333333333334,-10.508333333333333,10.9125,14.388333333333334,14.388333333333334,29.1 +14.437777777777777,-10.544444444444444,10.95,14.437777777777777,14.437777777777777,29.200000000000003 +14.487222222222222,-10.580555555555554,10.987499999999999,14.487222222222222,14.487222222222222,29.3 +14.536666666666667,-10.616666666666665,11.025,14.536666666666667,14.536666666666667,29.400000000000002 +14.58611111111111,-10.652777777777777,11.0625,14.58611111111111,14.58611111111111,29.5 +14.635555555555555,-10.688888888888888,11.1,14.635555555555555,14.635555555555555,29.6 +14.685,-10.725,11.1375,14.685,14.685,29.700000000000003 +14.734444444444444,-10.76111111111111,11.174999999999999,14.734444444444444,14.734444444444444,29.8 +14.783888888888889,-10.79722222222222,11.2125,14.783888888888889,14.783888888888889,29.900000000000002 +14.833333333333334,-10.833333333333332,11.25,14.833333333333334,14.833333333333334,30.0 +14.882777777777777,-10.869444444444444,11.2875,14.882777777777777,14.882777777777777,30.1 +14.932222222222222,-10.905555555555555,11.325,14.932222222222222,14.932222222222222,30.200000000000003 +14.981666666666666,-10.941666666666666,11.362499999999999,14.981666666666666,14.981666666666666,30.3 +15.03111111111111,-10.977777777777776,11.4,15.03111111111111,15.03111111111111,30.400000000000002 +15.080555555555556,-11.013888888888888,11.4375,15.080555555555556,15.080555555555556,30.5 +15.129999999999999,-11.049999999999999,11.475,15.129999999999999,15.129999999999999,30.6 +15.179444444444444,-11.08611111111111,11.5125,15.179444444444444,15.179444444444444,30.700000000000003 +15.22888888888889,-11.122222222222222,11.549999999999999,15.22888888888889,15.22888888888889,30.8 +15.278333333333332,-11.158333333333331,11.5875,15.278333333333332,15.278333333333332,30.900000000000002 +15.327777777777778,-11.194444444444443,11.625,15.327777777777778,15.327777777777778,31.0 +15.377222222222223,-11.230555555555554,11.6625,15.377222222222223,15.377222222222223,31.1 +15.426666666666666,-11.266666666666666,11.7,15.426666666666666,15.426666666666666,31.200000000000003 +15.476111111111111,-11.302777777777777,11.737499999999999,15.476111111111111,15.476111111111111,31.3 +15.525555555555556,-11.338888888888889,11.775,15.525555555555556,15.525555555555556,31.400000000000002 +15.575,-11.374999999999998,11.8125,15.575,15.575,31.5 +15.624444444444444,-11.41111111111111,11.85,15.624444444444444,15.624444444444444,31.6 +15.67388888888889,-11.447222222222221,11.8875,15.67388888888889,15.67388888888889,31.700000000000003 +15.723333333333333,-11.483333333333333,11.924999999999999,15.723333333333333,15.723333333333333,31.8 +15.772777777777778,-11.519444444444444,11.9625,15.772777777777778,15.772777777777778,31.900000000000002 +15.822222222222223,-11.555555555555554,12.0,15.822222222222223,15.822222222222223,32.0 +15.871666666666666,-11.591666666666665,12.0375,15.871666666666666,15.871666666666666,32.1 +15.921111111111111,-11.627777777777776,12.075,15.921111111111111,15.921111111111111,32.2 +15.970555555555555,-11.663888888888888,12.112499999999999,15.970555555555555,15.970555555555555,32.300000000000004 +16.02,-11.7,12.15,16.02,16.02,32.4 +16.069444444444443,-11.73611111111111,12.1875,16.069444444444443,16.069444444444443,32.5 +16.11888888888889,-11.77222222222222,12.225,16.11888888888889,16.11888888888889,32.6 +16.168333333333333,-11.808333333333332,12.2625,16.168333333333333,16.168333333333333,32.7 +16.217777777777776,-11.844444444444443,12.299999999999999,16.217777777777776,16.217777777777776,32.800000000000004 +16.267222222222223,-11.880555555555555,12.3375,16.267222222222223,16.267222222222223,32.9 +16.316666666666666,-11.916666666666666,12.375,16.316666666666666,16.316666666666666,33.0 +16.36611111111111,-11.952777777777778,12.4125,16.36611111111111,16.36611111111111,33.1 +16.415555555555557,-11.988888888888887,12.45,16.415555555555557,16.415555555555557,33.2 +16.465,-12.024999999999999,12.487499999999999,16.465,16.465,33.300000000000004 +16.514444444444443,-12.06111111111111,12.525,16.514444444444443,16.514444444444443,33.4 +16.56388888888889,-12.097222222222221,12.5625,16.56388888888889,16.56388888888889,33.5 +16.613333333333333,-12.133333333333333,12.6,16.613333333333333,16.613333333333333,33.6 +16.662777777777777,-12.169444444444443,12.6375,16.662777777777777,16.662777777777777,33.7 +16.712222222222223,-12.205555555555554,12.674999999999999,16.712222222222223,16.712222222222223,33.800000000000004 +16.761666666666667,-12.241666666666665,12.7125,16.761666666666667,16.761666666666667,33.9 +16.81111111111111,-12.277777777777777,12.75,16.81111111111111,16.81111111111111,34.0 +16.860555555555557,-12.313888888888888,12.7875,16.860555555555557,16.860555555555557,34.1 +16.91,-12.35,12.825,16.91,16.91,34.2 +16.959444444444443,-12.38611111111111,12.862499999999999,16.959444444444443,16.959444444444443,34.300000000000004 +17.00888888888889,-12.42222222222222,12.9,17.00888888888889,17.00888888888889,34.4 +17.058333333333334,-12.458333333333332,12.9375,17.058333333333334,17.058333333333334,34.5 +17.107777777777777,-12.494444444444444,12.975,17.107777777777777,17.107777777777777,34.6 +17.157222222222224,-12.530555555555555,13.0125,17.157222222222224,17.157222222222224,34.7 +17.206666666666667,-12.566666666666665,13.049999999999999,17.206666666666667,17.206666666666667,34.800000000000004 +17.25611111111111,-12.602777777777776,13.0875,17.25611111111111,17.25611111111111,34.9 +17.305555555555554,-12.638888888888888,13.125,17.305555555555554,17.305555555555554,35.0 +17.355,-12.674999999999999,13.1625,17.355,17.355,35.1 +17.404444444444444,-12.71111111111111,13.2,17.404444444444444,17.404444444444444,35.2 +17.453888888888887,-12.747222222222222,13.237499999999999,17.453888888888887,17.453888888888887,35.300000000000004 +17.503333333333334,-12.783333333333331,13.275,17.503333333333334,17.503333333333334,35.4 +17.552777777777777,-12.819444444444443,13.3125,17.552777777777777,17.552777777777777,35.5 +17.60222222222222,-12.855555555555554,13.35,17.60222222222222,17.60222222222222,35.6 +17.651666666666667,-12.891666666666666,13.3875,17.651666666666667,17.651666666666667,35.7 +17.70111111111111,-12.927777777777777,13.424999999999999,17.70111111111111,17.70111111111111,35.800000000000004 +17.750555555555554,-12.963888888888887,13.4625,17.750555555555554,17.750555555555554,35.9 +17.8,-12.999999999999998,13.5,17.8,17.8,36.0 +17.849444444444444,-13.03611111111111,13.5375,17.849444444444444,17.849444444444444,36.1 +17.898888888888887,-13.072222222222221,13.575,17.898888888888887,17.898888888888887,36.2 +17.948333333333334,-13.108333333333333,13.612499999999999,17.948333333333334,17.948333333333334,36.300000000000004 +17.997777777777777,-13.144444444444444,13.65,17.997777777777777,17.997777777777777,36.4 +18.04722222222222,-13.180555555555554,13.6875,18.04722222222222,18.04722222222222,36.5 +18.096666666666668,-13.216666666666665,13.725,18.096666666666668,18.096666666666668,36.6 +18.14611111111111,-13.252777777777776,13.7625,18.14611111111111,18.14611111111111,36.7 +18.195555555555554,-13.288888888888888,13.799999999999999,18.195555555555554,18.195555555555554,36.800000000000004 +18.245,-13.325,13.8375,18.245,18.245,36.9 +18.294444444444444,-13.36111111111111,13.875,18.294444444444444,18.294444444444444,37.0 +18.343888888888888,-13.39722222222222,13.9125,18.343888888888888,18.343888888888888,37.1 +18.393333333333334,-13.433333333333332,13.95,18.393333333333334,18.393333333333334,37.2 +18.442777777777778,-13.469444444444443,13.987499999999999,18.442777777777778,18.442777777777778,37.300000000000004 +18.49222222222222,-13.505555555555555,14.025,18.49222222222222,18.49222222222222,37.4 +18.541666666666668,-13.541666666666666,14.0625,18.541666666666668,18.541666666666668,37.5 +18.59111111111111,-13.577777777777776,14.1,18.59111111111111,18.59111111111111,37.6 +18.640555555555554,-13.613888888888887,14.1375,18.640555555555554,18.640555555555554,37.7 +18.69,-13.649999999999999,14.174999999999999,18.69,18.69,37.800000000000004 +18.739444444444445,-13.68611111111111,14.2125,18.739444444444445,18.739444444444445,37.9 +18.788888888888888,-13.722222222222221,14.25,18.788888888888888,18.788888888888888,38.0 +18.838333333333335,-13.758333333333333,14.2875,18.838333333333335,18.838333333333335,38.1 +18.887777777777778,-13.794444444444443,14.325,18.887777777777778,18.887777777777778,38.2 +18.93722222222222,-13.830555555555554,14.362499999999999,18.93722222222222,18.93722222222222,38.300000000000004 +18.986666666666665,-13.866666666666665,14.399999999999999,18.986666666666665,18.986666666666665,38.400000000000006 +19.03611111111111,-13.902777777777777,14.4375,19.03611111111111,19.03611111111111,38.5 +19.085555555555555,-13.938888888888888,14.475,19.085555555555555,19.085555555555555,38.6 +19.134999999999998,-13.974999999999998,14.5125,19.134999999999998,19.134999999999998,38.7 +19.184444444444445,-14.01111111111111,14.549999999999999,19.184444444444445,19.184444444444445,38.800000000000004 +19.233888888888888,-14.04722222222222,14.587499999999999,19.233888888888888,19.233888888888888,38.900000000000006 +19.28333333333333,-14.083333333333332,14.625,19.28333333333333,19.28333333333333,39.0 +19.33277777777778,-14.119444444444444,14.6625,19.33277777777778,19.33277777777778,39.1 +19.38222222222222,-14.155555555555555,14.7,19.38222222222222,19.38222222222222,39.2 +19.431666666666665,-14.191666666666665,14.737499999999999,19.431666666666665,19.431666666666665,39.300000000000004 +19.48111111111111,-14.227777777777776,14.774999999999999,19.48111111111111,19.48111111111111,39.400000000000006 +19.530555555555555,-14.263888888888888,14.8125,19.530555555555555,19.530555555555555,39.5 +19.58,-14.299999999999999,14.85,19.58,19.58,39.6 +19.629444444444445,-14.33611111111111,14.8875,19.629444444444445,19.629444444444445,39.7 +19.67888888888889,-14.37222222222222,14.924999999999999,19.67888888888889,19.67888888888889,39.800000000000004 +19.72833333333333,-14.408333333333331,14.962499999999999,19.72833333333333,19.72833333333333,39.900000000000006 +19.77777777777778,-14.444444444444443,15.0,19.77777777777778,19.77777777777778,40.0 +19.827222222222222,-14.480555555555554,15.0375,19.827222222222222,19.827222222222222,40.1 +19.876666666666665,-14.516666666666666,15.075,19.876666666666665,19.876666666666665,40.2 +19.926111111111112,-14.552777777777777,15.112499999999999,19.926111111111112,19.926111111111112,40.300000000000004 +19.975555555555555,-14.588888888888887,15.149999999999999,19.975555555555555,19.975555555555555,40.400000000000006 +20.025,-14.624999999999998,15.1875,20.025,20.025,40.5 +20.074444444444445,-14.66111111111111,15.225,20.074444444444445,20.074444444444445,40.6 +20.12388888888889,-14.697222222222221,15.2625,20.12388888888889,20.12388888888889,40.7 +20.173333333333332,-14.733333333333333,15.299999999999999,20.173333333333332,20.173333333333332,40.800000000000004 +20.22277777777778,-14.769444444444444,15.337499999999999,20.22277777777778,20.22277777777778,40.900000000000006 +20.272222222222222,-14.805555555555554,15.375,20.272222222222222,20.272222222222222,41.0 +20.321666666666665,-14.841666666666665,15.4125,20.321666666666665,20.321666666666665,41.1 +20.371111111111112,-14.877777777777776,15.45,20.371111111111112,20.371111111111112,41.2 +20.420555555555556,-14.913888888888888,15.487499999999999,20.420555555555556,20.420555555555556,41.300000000000004 +20.47,-14.95,15.524999999999999,20.47,20.47,41.400000000000006 +20.519444444444446,-14.986111111111109,15.5625,20.519444444444446,20.519444444444446,41.5 +20.56888888888889,-15.02222222222222,15.6,20.56888888888889,20.56888888888889,41.6 +20.618333333333332,-15.058333333333332,15.6375,20.618333333333332,20.618333333333332,41.7 +20.66777777777778,-15.094444444444443,15.674999999999999,20.66777777777778,20.66777777777778,41.800000000000004 +20.717222222222222,-15.130555555555555,15.712499999999999,20.717222222222222,20.717222222222222,41.900000000000006 +20.766666666666666,-15.166666666666666,15.75,20.766666666666666,20.766666666666666,42.0 +20.81611111111111,-15.202777777777776,15.7875,20.81611111111111,20.81611111111111,42.1 +20.865555555555556,-15.238888888888887,15.825,20.865555555555556,20.865555555555556,42.2 +20.915,-15.274999999999999,15.862499999999999,20.915,20.915,42.300000000000004 +20.964444444444442,-15.31111111111111,15.899999999999999,20.964444444444442,20.964444444444442,42.400000000000006 +21.01388888888889,-15.347222222222221,15.9375,21.01388888888889,21.01388888888889,42.5 +21.063333333333333,-15.383333333333331,15.975,21.063333333333333,21.063333333333333,42.6 +21.112777777777776,-15.419444444444443,16.0125,21.112777777777776,21.112777777777776,42.7 +21.162222222222223,-15.455555555555554,16.05,21.162222222222223,21.162222222222223,42.800000000000004 +21.211666666666666,-15.491666666666665,16.0875,21.211666666666666,21.211666666666666,42.900000000000006 +21.26111111111111,-15.527777777777777,16.125,21.26111111111111,21.26111111111111,43.0 +21.310555555555556,-15.563888888888888,16.162499999999998,21.310555555555556,21.310555555555556,43.1 +21.36,-15.599999999999998,16.2,21.36,21.36,43.2 +21.409444444444443,-15.63611111111111,16.2375,21.409444444444443,21.409444444444443,43.300000000000004 +21.45888888888889,-15.67222222222222,16.275,21.45888888888889,21.45888888888889,43.400000000000006 +21.508333333333333,-15.708333333333332,16.3125,21.508333333333333,21.508333333333333,43.5 +21.557777777777776,-15.744444444444444,16.349999999999998,21.557777777777776,21.557777777777776,43.6 +21.607222222222223,-15.780555555555553,16.3875,21.607222222222223,21.607222222222223,43.7 +21.656666666666666,-15.816666666666665,16.425,21.656666666666666,21.656666666666666,43.800000000000004 +21.70611111111111,-15.852777777777776,16.4625,21.70611111111111,21.70611111111111,43.900000000000006 +21.755555555555556,-15.888888888888888,16.5,21.755555555555556,21.755555555555556,44.0 +21.805,-15.924999999999999,16.537499999999998,21.805,21.805,44.1 +21.854444444444443,-15.96111111111111,16.575,21.854444444444443,21.854444444444443,44.2 +21.90388888888889,-15.99722222222222,16.6125,21.90388888888889,21.90388888888889,44.300000000000004 +21.953333333333333,-16.03333333333333,16.65,21.953333333333333,21.953333333333333,44.400000000000006 +22.002777777777776,-16.069444444444443,16.6875,22.002777777777776,22.002777777777776,44.5 +22.052222222222223,-16.105555555555554,16.724999999999998,22.052222222222223,22.052222222222223,44.6 +22.101666666666667,-16.141666666666666,16.7625,22.101666666666667,22.101666666666667,44.7 +22.15111111111111,-16.177777777777777,16.8,22.15111111111111,22.15111111111111,44.800000000000004 +22.200555555555557,-16.21388888888889,16.8375,22.200555555555557,22.200555555555557,44.900000000000006 +22.25,-16.25,16.875,22.25,22.25,45.0 +22.299444444444443,-16.286111111111108,16.912499999999998,22.299444444444443,22.299444444444443,45.1 +22.34888888888889,-16.32222222222222,16.95,22.34888888888889,22.34888888888889,45.2 +22.398333333333333,-16.35833333333333,16.9875,22.398333333333333,22.398333333333333,45.300000000000004 +22.447777777777777,-16.394444444444442,17.025,22.447777777777777,22.447777777777777,45.400000000000006 +22.497222222222224,-16.430555555555554,17.0625,22.497222222222224,22.497222222222224,45.5 +22.546666666666667,-16.466666666666665,17.099999999999998,22.546666666666667,22.546666666666667,45.6 +22.59611111111111,-16.502777777777776,17.1375,22.59611111111111,22.59611111111111,45.7 +22.645555555555553,-16.538888888888888,17.175,22.645555555555553,22.645555555555553,45.800000000000004 +22.695,-16.575,17.2125,22.695,22.695,45.900000000000006 +22.744444444444444,-16.61111111111111,17.25,22.744444444444444,22.744444444444444,46.0 +22.793888888888887,-16.647222222222222,17.287499999999998,22.793888888888887,22.793888888888887,46.1 +22.843333333333334,-16.68333333333333,17.325,22.843333333333334,22.843333333333334,46.2 +22.892777777777777,-16.71944444444444,17.3625,22.892777777777777,22.892777777777777,46.300000000000004 +22.94222222222222,-16.755555555555553,17.4,22.94222222222222,22.94222222222222,46.400000000000006 +22.991666666666667,-16.791666666666664,17.4375,22.991666666666667,22.991666666666667,46.5 +23.04111111111111,-16.827777777777776,17.474999999999998,23.04111111111111,23.04111111111111,46.6 +23.090555555555554,-16.863888888888887,17.5125,23.090555555555554,23.090555555555554,46.7 +23.14,-16.9,17.55,23.14,23.14,46.800000000000004 +23.189444444444444,-16.93611111111111,17.5875,23.189444444444444,23.189444444444444,46.900000000000006 +23.238888888888887,-16.97222222222222,17.625,23.238888888888887,23.238888888888887,47.0 +23.288333333333334,-17.008333333333333,17.662499999999998,23.288333333333334,23.288333333333334,47.1 +23.337777777777777,-17.044444444444444,17.7,23.337777777777777,23.337777777777777,47.2 +23.38722222222222,-17.080555555555556,17.7375,23.38722222222222,23.38722222222222,47.300000000000004 +23.436666666666667,-17.116666666666664,17.775,23.436666666666667,23.436666666666667,47.400000000000006 +23.48611111111111,-17.152777777777775,17.8125,23.48611111111111,23.48611111111111,47.5 +23.535555555555554,-17.188888888888886,17.849999999999998,23.535555555555554,23.535555555555554,47.6 +23.585,-17.224999999999998,17.8875,23.585,23.585,47.7 +23.634444444444444,-17.26111111111111,17.925,23.634444444444444,23.634444444444444,47.800000000000004 +23.683888888888887,-17.29722222222222,17.9625,23.683888888888887,23.683888888888887,47.900000000000006 +23.733333333333334,-17.333333333333332,18.0,23.733333333333334,23.733333333333334,48.0 +23.782777777777778,-17.369444444444444,18.037499999999998,23.782777777777778,23.782777777777778,48.1 +23.83222222222222,-17.405555555555555,18.075,23.83222222222222,23.83222222222222,48.2 +23.881666666666668,-17.441666666666666,18.1125,23.881666666666668,23.881666666666668,48.300000000000004 +23.93111111111111,-17.477777777777778,18.15,23.93111111111111,23.93111111111111,48.400000000000006 +23.980555555555554,-17.513888888888886,18.1875,23.980555555555554,23.980555555555554,48.5 +24.03,-17.549999999999997,18.224999999999998,24.03,24.03,48.6 +24.079444444444444,-17.58611111111111,18.2625,24.079444444444444,24.079444444444444,48.7 +24.128888888888888,-17.62222222222222,18.3,24.128888888888888,24.128888888888888,48.800000000000004 +24.178333333333335,-17.65833333333333,18.3375,24.178333333333335,24.178333333333335,48.900000000000006 +24.227777777777778,-17.694444444444443,18.375,24.227777777777778,24.227777777777778,49.0 +24.27722222222222,-17.730555555555554,18.412499999999998,24.27722222222222,24.27722222222222,49.1 +24.326666666666668,-17.766666666666666,18.45,24.326666666666668,24.326666666666668,49.2 +24.37611111111111,-17.802777777777777,18.4875,24.37611111111111,24.37611111111111,49.300000000000004 +24.425555555555555,-17.83888888888889,18.525,24.425555555555555,24.425555555555555,49.400000000000006 +24.474999999999998,-17.875,18.5625,24.474999999999998,24.474999999999998,49.5 +24.524444444444445,-17.911111111111108,18.599999999999998,24.524444444444445,24.524444444444445,49.6 +24.573888888888888,-17.94722222222222,18.6375,24.573888888888888,24.573888888888888,49.7 +24.62333333333333,-17.98333333333333,18.675,24.62333333333333,24.62333333333333,49.800000000000004 +24.672777777777778,-18.019444444444442,18.7125,24.672777777777778,24.672777777777778,49.900000000000006 +24.72222222222222,-18.055555555555554,18.75,24.72222222222222,24.72222222222222,50.0 +24.771666666666665,-18.091666666666665,18.787499999999998,24.771666666666665,24.771666666666665,50.1 +24.82111111111111,-18.127777777777776,18.825,24.82111111111111,24.82111111111111,50.2 +24.870555555555555,-18.163888888888888,18.8625,24.870555555555555,24.870555555555555,50.300000000000004 +24.919999999999998,-18.2,18.9,24.919999999999998,24.919999999999998,50.400000000000006 +24.969444444444445,-18.23611111111111,18.9375,24.969444444444445,24.969444444444445,50.5 +25.01888888888889,-18.272222222222222,18.974999999999998,25.01888888888889,25.01888888888889,50.6 +25.06833333333333,-18.30833333333333,19.0125,25.06833333333333,25.06833333333333,50.7 +25.11777777777778,-18.34444444444444,19.05,25.11777777777778,25.11777777777778,50.800000000000004 +25.16722222222222,-18.380555555555553,19.0875,25.16722222222222,25.16722222222222,50.900000000000006 +25.216666666666665,-18.416666666666664,19.125,25.216666666666665,25.216666666666665,51.0 +25.266111111111112,-18.452777777777776,19.162499999999998,25.266111111111112,25.266111111111112,51.1 +25.315555555555555,-18.488888888888887,19.2,25.315555555555555,25.315555555555555,51.2 +25.365,-18.525,19.2375,25.365,25.365,51.300000000000004 +25.414444444444445,-18.56111111111111,19.275,25.414444444444445,25.414444444444445,51.400000000000006 +25.46388888888889,-18.59722222222222,19.3125,25.46388888888889,25.46388888888889,51.5 +25.513333333333332,-18.633333333333333,19.349999999999998,25.513333333333332,25.513333333333332,51.6 +25.56277777777778,-18.669444444444444,19.3875,25.56277777777778,25.56277777777778,51.7 +25.612222222222222,-18.705555555555552,19.425,25.612222222222222,25.612222222222222,51.800000000000004 +25.661666666666665,-18.741666666666664,19.4625,25.661666666666665,25.661666666666665,51.900000000000006 +25.711111111111112,-18.777777777777775,19.5,25.711111111111112,25.711111111111112,52.0 +25.760555555555555,-18.813888888888886,19.537499999999998,25.760555555555555,25.760555555555555,52.1 +25.81,-18.849999999999998,19.575,25.81,25.81,52.2 +25.859444444444446,-18.88611111111111,19.6125,25.859444444444446,25.859444444444446,52.300000000000004 +25.90888888888889,-18.92222222222222,19.65,25.90888888888889,25.90888888888889,52.400000000000006 +25.958333333333332,-18.958333333333332,19.6875,25.958333333333332,25.958333333333332,52.5 +26.00777777777778,-18.994444444444444,19.724999999999998,26.00777777777778,26.00777777777778,52.6 +26.057222222222222,-19.030555555555555,19.7625,26.057222222222222,26.057222222222222,52.7 +26.106666666666666,-19.066666666666666,19.8,26.106666666666666,26.106666666666666,52.800000000000004 +26.156111111111112,-19.102777777777774,19.8375,26.156111111111112,26.156111111111112,52.900000000000006 +26.205555555555556,-19.138888888888886,19.875,26.205555555555556,26.205555555555556,53.0 +26.255,-19.174999999999997,19.912499999999998,26.255,26.255,53.1 +26.304444444444442,-19.21111111111111,19.95,26.304444444444442,26.304444444444442,53.2 +26.35388888888889,-19.24722222222222,19.9875,26.35388888888889,26.35388888888889,53.300000000000004 +26.403333333333332,-19.28333333333333,20.025,26.403333333333332,26.403333333333332,53.400000000000006 +26.452777777777776,-19.319444444444443,20.0625,26.452777777777776,26.452777777777776,53.5 +26.502222222222223,-19.355555555555554,20.099999999999998,26.502222222222223,26.502222222222223,53.6 +26.551666666666666,-19.391666666666666,20.1375,26.551666666666666,26.551666666666666,53.7 +26.60111111111111,-19.427777777777777,20.175,26.60111111111111,26.60111111111111,53.800000000000004 +26.650555555555556,-19.46388888888889,20.2125,26.650555555555556,26.650555555555556,53.900000000000006 +26.7,-19.499999999999996,20.25,26.7,26.7,54.0 +26.749444444444443,-19.536111111111108,20.287499999999998,26.749444444444443,26.749444444444443,54.1 +26.79888888888889,-19.57222222222222,20.325,26.79888888888889,26.79888888888889,54.2 +26.848333333333333,-19.60833333333333,20.3625,26.848333333333333,26.848333333333333,54.300000000000004 +26.897777777777776,-19.644444444444442,20.4,26.897777777777776,26.897777777777776,54.400000000000006 +26.947222222222223,-19.680555555555554,20.4375,26.947222222222223,26.947222222222223,54.5 +26.996666666666666,-19.716666666666665,20.474999999999998,26.996666666666666,26.996666666666666,54.6 +27.04611111111111,-19.752777777777776,20.5125,27.04611111111111,27.04611111111111,54.7 +27.095555555555556,-19.788888888888888,20.55,27.095555555555556,27.095555555555556,54.800000000000004 +27.145,-19.825,20.5875,27.145,27.145,54.900000000000006 +27.194444444444443,-19.86111111111111,20.625,27.194444444444443,27.194444444444443,55.0 +27.24388888888889,-19.89722222222222,20.662499999999998,27.24388888888889,27.24388888888889,55.1 +27.293333333333333,-19.93333333333333,20.7,27.293333333333333,27.293333333333333,55.2 +27.342777777777776,-19.96944444444444,20.7375,27.342777777777776,27.342777777777776,55.300000000000004 +27.392222222222223,-20.005555555555553,20.775,27.392222222222223,27.392222222222223,55.400000000000006 +27.441666666666666,-20.041666666666664,20.8125,27.441666666666666,27.441666666666666,55.5 +27.49111111111111,-20.077777777777776,20.849999999999998,27.49111111111111,27.49111111111111,55.6 +27.540555555555557,-20.113888888888887,20.8875,27.540555555555557,27.540555555555557,55.7 +27.59,-20.15,20.925,27.59,27.59,55.800000000000004 +27.639444444444443,-20.18611111111111,20.9625,27.639444444444443,27.639444444444443,55.900000000000006 +27.68888888888889,-20.22222222222222,21.0,27.68888888888889,27.68888888888889,56.0 +27.738333333333333,-20.258333333333333,21.037499999999998,27.738333333333333,27.738333333333333,56.1 +27.787777777777777,-20.294444444444444,21.075,27.787777777777777,27.787777777777777,56.2 +27.837222222222223,-20.330555555555552,21.1125,27.837222222222223,27.837222222222223,56.300000000000004 +27.886666666666667,-20.366666666666664,21.15,27.886666666666667,27.886666666666667,56.400000000000006 +27.93611111111111,-20.402777777777775,21.1875,27.93611111111111,27.93611111111111,56.5 +27.985555555555557,-20.438888888888886,21.224999999999998,27.985555555555557,27.985555555555557,56.6 +28.035,-20.474999999999998,21.2625,28.035,28.035,56.7 +28.084444444444443,-20.51111111111111,21.3,28.084444444444443,28.084444444444443,56.800000000000004 +28.133888888888887,-20.54722222222222,21.3375,28.133888888888887,28.133888888888887,56.900000000000006 +28.183333333333334,-20.583333333333332,21.375,28.183333333333334,28.183333333333334,57.0 +28.232777777777777,-20.619444444444444,21.412499999999998,28.232777777777777,28.232777777777777,57.1 +28.28222222222222,-20.655555555555555,21.45,28.28222222222222,28.28222222222222,57.2 +28.331666666666667,-20.691666666666666,21.4875,28.331666666666667,28.331666666666667,57.300000000000004 +28.38111111111111,-20.727777777777774,21.525,28.38111111111111,28.38111111111111,57.400000000000006 +28.430555555555554,-20.763888888888886,21.5625,28.430555555555554,28.430555555555554,57.5 +28.48,-20.799999999999997,21.599999999999998,28.48,28.48,57.6 +28.529444444444444,-20.83611111111111,21.6375,28.529444444444444,28.529444444444444,57.7 +28.578888888888887,-20.87222222222222,21.675,28.578888888888887,28.578888888888887,57.800000000000004 +28.628333333333334,-20.90833333333333,21.7125,28.628333333333334,28.628333333333334,57.900000000000006 +28.677777777777777,-20.944444444444443,21.75,28.677777777777777,28.677777777777777,58.0 +28.72722222222222,-20.980555555555554,21.787499999999998,28.72722222222222,28.72722222222222,58.1 +28.776666666666667,-21.016666666666666,21.825,28.776666666666667,28.776666666666667,58.2 +28.82611111111111,-21.052777777777777,21.8625,28.82611111111111,28.82611111111111,58.300000000000004 +28.875555555555554,-21.08888888888889,21.9,28.875555555555554,28.875555555555554,58.400000000000006 +28.925,-21.124999999999996,21.9375,28.925,28.925,58.5 +28.974444444444444,-21.161111111111108,21.974999999999998,28.974444444444444,28.974444444444444,58.6 +29.023888888888887,-21.19722222222222,22.0125,29.023888888888887,29.023888888888887,58.7 +29.073333333333334,-21.23333333333333,22.05,29.073333333333334,29.073333333333334,58.800000000000004 +29.122777777777777,-21.269444444444442,22.0875,29.122777777777777,29.122777777777777,58.900000000000006 +29.17222222222222,-21.305555555555554,22.125,29.17222222222222,29.17222222222222,59.0 +29.221666666666668,-21.341666666666665,22.162499999999998,29.221666666666668,29.221666666666668,59.1 +29.27111111111111,-21.377777777777776,22.2,29.27111111111111,29.27111111111111,59.2 +29.320555555555554,-21.413888888888888,22.2375,29.320555555555554,29.320555555555554,59.300000000000004 +29.37,-21.45,22.275,29.37,29.37,59.400000000000006 +29.419444444444444,-21.48611111111111,22.3125,29.419444444444444,29.419444444444444,59.5 +29.468888888888888,-21.52222222222222,22.349999999999998,29.468888888888888,29.468888888888888,59.6 +29.518333333333334,-21.55833333333333,22.3875,29.518333333333334,29.518333333333334,59.7 +29.567777777777778,-21.59444444444444,22.425,29.567777777777778,29.567777777777778,59.800000000000004 +29.61722222222222,-21.630555555555553,22.4625,29.61722222222222,29.61722222222222,59.900000000000006 +29.666666666666668,-21.666666666666664,22.5,29.666666666666668,29.666666666666668,60.0 +29.71611111111111,-21.702777777777776,22.537499999999998,29.71611111111111,29.71611111111111,60.1 +29.765555555555554,-21.738888888888887,22.575,29.765555555555554,29.765555555555554,60.2 +29.815,-21.775,22.6125,29.815,29.815,60.300000000000004 +29.864444444444445,-21.81111111111111,22.65,29.864444444444445,29.864444444444445,60.400000000000006 +29.913888888888888,-21.84722222222222,22.6875,29.913888888888888,29.913888888888888,60.5 +29.96333333333333,-21.883333333333333,22.724999999999998,29.96333333333333,29.96333333333333,60.6 +30.012777777777778,-21.91944444444444,22.7625,30.012777777777778,30.012777777777778,60.7 +30.06222222222222,-21.955555555555552,22.8,30.06222222222222,30.06222222222222,60.800000000000004 +30.111666666666665,-21.991666666666664,22.8375,30.111666666666665,30.111666666666665,60.900000000000006 +30.16111111111111,-22.027777777777775,22.875,30.16111111111111,30.16111111111111,61.0 +30.210555555555555,-22.063888888888886,22.912499999999998,30.210555555555555,30.210555555555555,61.1 +30.259999999999998,-22.099999999999998,22.95,30.259999999999998,30.259999999999998,61.2 +30.309444444444445,-22.13611111111111,22.9875,30.309444444444445,30.309444444444445,61.300000000000004 +30.358888888888888,-22.17222222222222,23.025,30.358888888888888,30.358888888888888,61.400000000000006 +30.40833333333333,-22.208333333333332,23.0625,30.40833333333333,30.40833333333333,61.5 +30.45777777777778,-22.244444444444444,23.099999999999998,30.45777777777778,30.45777777777778,61.6 +30.50722222222222,-22.280555555555555,23.1375,30.50722222222222,30.50722222222222,61.7 +30.556666666666665,-22.316666666666663,23.175,30.556666666666665,30.556666666666665,61.800000000000004 +30.60611111111111,-22.352777777777774,23.2125,30.60611111111111,30.60611111111111,61.900000000000006 +30.655555555555555,-22.388888888888886,23.25,30.655555555555555,30.655555555555555,62.0 +30.705,-22.424999999999997,23.287499999999998,30.705,30.705,62.1 +30.754444444444445,-22.46111111111111,23.325,30.754444444444445,30.754444444444445,62.2 +30.80388888888889,-22.49722222222222,23.3625,30.80388888888889,30.80388888888889,62.300000000000004 +30.85333333333333,-22.53333333333333,23.4,30.85333333333333,30.85333333333333,62.400000000000006 +30.90277777777778,-22.569444444444443,23.4375,30.90277777777778,30.90277777777778,62.5 +30.952222222222222,-22.605555555555554,23.474999999999998,30.952222222222222,30.952222222222222,62.6 +31.001666666666665,-22.641666666666666,23.5125,31.001666666666665,31.001666666666665,62.7 +31.051111111111112,-22.677777777777777,23.55,31.051111111111112,31.051111111111112,62.800000000000004 +31.100555555555555,-22.713888888888885,23.5875,31.100555555555555,31.100555555555555,62.900000000000006 +31.15,-22.749999999999996,23.625,31.15,31.15,63.0 +31.199444444444445,-22.786111111111108,23.662499999999998,31.199444444444445,31.199444444444445,63.1 +31.24888888888889,-22.82222222222222,23.7,31.24888888888889,31.24888888888889,63.2 +31.298333333333332,-22.85833333333333,23.7375,31.298333333333332,31.298333333333332,63.300000000000004 +31.34777777777778,-22.894444444444442,23.775,31.34777777777778,31.34777777777778,63.400000000000006 +31.397222222222222,-22.930555555555554,23.8125,31.397222222222222,31.397222222222222,63.5 +31.446666666666665,-22.966666666666665,23.849999999999998,31.446666666666665,31.446666666666665,63.6 +31.496111111111112,-23.002777777777776,23.8875,31.496111111111112,31.496111111111112,63.7 +31.545555555555556,-23.038888888888888,23.925,31.545555555555556,31.545555555555556,63.800000000000004 +31.595,-23.075,23.9625,31.595,31.595,63.900000000000006 +31.644444444444446,-23.111111111111107,24.0,31.644444444444446,31.644444444444446,64.0 +31.69388888888889,-23.14722222222222,24.037499999999998,31.69388888888889,31.69388888888889,64.10000000000001 +31.743333333333332,-23.18333333333333,24.075,31.743333333333332,31.743333333333332,64.2 +31.792777777777776,-23.21944444444444,24.1125,31.792777777777776,31.792777777777776,64.3 +31.842222222222222,-23.255555555555553,24.15,31.842222222222222,31.842222222222222,64.4 +31.891666666666666,-23.291666666666664,24.1875,31.891666666666666,31.891666666666666,64.5 +31.94111111111111,-23.327777777777776,24.224999999999998,31.94111111111111,31.94111111111111,64.60000000000001 +31.990555555555556,-23.363888888888887,24.2625,31.990555555555556,31.990555555555556,64.7 +32.04,-23.4,24.3,32.04,32.04,64.8 +32.089444444444446,-23.43611111111111,24.3375,32.089444444444446,32.089444444444446,64.9 +32.138888888888886,-23.47222222222222,24.375,32.138888888888886,32.138888888888886,65.0 +32.18833333333333,-23.508333333333333,24.412499999999998,32.18833333333333,32.18833333333333,65.10000000000001 +32.23777777777778,-23.54444444444444,24.45,32.23777777777778,32.23777777777778,65.2 +32.28722222222222,-23.580555555555552,24.4875,32.28722222222222,32.28722222222222,65.3 +32.336666666666666,-23.616666666666664,24.525,32.336666666666666,32.336666666666666,65.4 +32.38611111111111,-23.652777777777775,24.5625,32.38611111111111,32.38611111111111,65.5 +32.43555555555555,-23.688888888888886,24.599999999999998,32.43555555555555,32.43555555555555,65.60000000000001 +32.485,-23.724999999999998,24.6375,32.485,32.485,65.7 +32.534444444444446,-23.76111111111111,24.675,32.534444444444446,32.534444444444446,65.8 +32.583888888888886,-23.79722222222222,24.7125,32.583888888888886,32.583888888888886,65.9 +32.63333333333333,-23.833333333333332,24.75,32.63333333333333,32.63333333333333,66.0 +32.68277777777778,-23.869444444444444,24.787499999999998,32.68277777777778,32.68277777777778,66.10000000000001 +32.73222222222222,-23.905555555555555,24.825,32.73222222222222,32.73222222222222,66.2 +32.781666666666666,-23.941666666666663,24.8625,32.781666666666666,32.781666666666666,66.3 +32.83111111111111,-23.977777777777774,24.9,32.83111111111111,32.83111111111111,66.4 +32.88055555555555,-24.013888888888886,24.9375,32.88055555555555,32.88055555555555,66.5 +32.93,-24.049999999999997,24.974999999999998,32.93,32.93,66.60000000000001 +32.97944444444445,-24.08611111111111,25.0125,32.97944444444445,32.97944444444445,66.7 +33.028888888888886,-24.12222222222222,25.05,33.028888888888886,33.028888888888886,66.8 +33.07833333333333,-24.15833333333333,25.0875,33.07833333333333,33.07833333333333,66.9 +33.12777777777778,-24.194444444444443,25.125,33.12777777777778,33.12777777777778,67.0 +33.17722222222222,-24.230555555555554,25.162499999999998,33.17722222222222,33.17722222222222,67.10000000000001 +33.22666666666667,-24.266666666666666,25.2,33.22666666666667,33.22666666666667,67.2 +33.27611111111111,-24.302777777777777,25.2375,33.27611111111111,33.27611111111111,67.3 +33.32555555555555,-24.338888888888885,25.275,33.32555555555555,33.32555555555555,67.4 +33.375,-24.374999999999996,25.3125,33.375,33.375,67.5 +33.42444444444445,-24.411111111111108,25.349999999999998,33.42444444444445,33.42444444444445,67.60000000000001 +33.47388888888889,-24.44722222222222,25.3875,33.47388888888889,33.47388888888889,67.7 +33.52333333333333,-24.48333333333333,25.425,33.52333333333333,33.52333333333333,67.8 +33.57277777777778,-24.519444444444442,25.4625,33.57277777777778,33.57277777777778,67.9 +33.62222222222222,-24.555555555555554,25.5,33.62222222222222,33.62222222222222,68.0 +33.67166666666667,-24.591666666666665,25.537499999999998,33.67166666666667,33.67166666666667,68.10000000000001 +33.721111111111114,-24.627777777777776,25.575,33.721111111111114,33.721111111111114,68.2 +33.77055555555555,-24.663888888888888,25.6125,33.77055555555555,33.77055555555555,68.3 +33.82,-24.7,25.65,33.82,33.82,68.4 +33.86944444444445,-24.736111111111107,25.6875,33.86944444444445,33.86944444444445,68.5 +33.91888888888889,-24.77222222222222,25.724999999999998,33.91888888888889,33.91888888888889,68.60000000000001 +33.968333333333334,-24.80833333333333,25.7625,33.968333333333334,33.968333333333334,68.7 +34.01777777777778,-24.84444444444444,25.8,34.01777777777778,34.01777777777778,68.8 +34.06722222222222,-24.880555555555553,25.8375,34.06722222222222,34.06722222222222,68.9 +34.11666666666667,-24.916666666666664,25.875,34.11666666666667,34.11666666666667,69.0 +34.166111111111114,-24.952777777777776,25.912499999999998,34.166111111111114,34.166111111111114,69.10000000000001 +34.215555555555554,-24.988888888888887,25.95,34.215555555555554,34.215555555555554,69.2 +34.265,-25.025,25.9875,34.265,34.265,69.3 +34.31444444444445,-25.06111111111111,26.025,34.31444444444445,34.31444444444445,69.4 +34.36388888888889,-25.09722222222222,26.0625,34.36388888888889,34.36388888888889,69.5 +34.413333333333334,-25.13333333333333,26.099999999999998,34.413333333333334,34.413333333333334,69.60000000000001 +34.462777777777774,-25.16944444444444,26.1375,34.462777777777774,34.462777777777774,69.7 +34.51222222222222,-25.205555555555552,26.175,34.51222222222222,34.51222222222222,69.8 +34.56166666666667,-25.241666666666664,26.2125,34.56166666666667,34.56166666666667,69.9 +34.61111111111111,-25.277777777777775,26.25,34.61111111111111,34.61111111111111,70.0 +34.660555555555554,-25.313888888888886,26.287499999999998,34.660555555555554,34.660555555555554,70.10000000000001 +34.71,-25.349999999999998,26.325,34.71,34.71,70.2 +34.75944444444444,-25.38611111111111,26.3625,34.75944444444444,34.75944444444444,70.3 +34.80888888888889,-25.42222222222222,26.4,34.80888888888889,34.80888888888889,70.4 +34.858333333333334,-25.458333333333332,26.4375,34.858333333333334,34.858333333333334,70.5 +34.907777777777774,-25.494444444444444,26.474999999999998,34.907777777777774,34.907777777777774,70.60000000000001 +34.95722222222222,-25.53055555555555,26.5125,34.95722222222222,34.95722222222222,70.7 +35.00666666666667,-25.566666666666663,26.55,35.00666666666667,35.00666666666667,70.8 +35.05611111111111,-25.602777777777774,26.5875,35.05611111111111,35.05611111111111,70.9 +35.105555555555554,-25.638888888888886,26.625,35.105555555555554,35.105555555555554,71.0 +35.155,-25.674999999999997,26.662499999999998,35.155,35.155,71.10000000000001 +35.20444444444444,-25.71111111111111,26.7,35.20444444444444,35.20444444444444,71.2 +35.25388888888889,-25.74722222222222,26.7375,35.25388888888889,35.25388888888889,71.3 +35.303333333333335,-25.78333333333333,26.775,35.303333333333335,35.303333333333335,71.4 +35.352777777777774,-25.819444444444443,26.8125,35.352777777777774,35.352777777777774,71.5 +35.40222222222222,-25.855555555555554,26.849999999999998,35.40222222222222,35.40222222222222,71.60000000000001 +35.45166666666667,-25.891666666666666,26.8875,35.45166666666667,35.45166666666667,71.7 +35.50111111111111,-25.927777777777774,26.925,35.50111111111111,35.50111111111111,71.8 +35.550555555555555,-25.963888888888885,26.9625,35.550555555555555,35.550555555555555,71.9 +35.6,-25.999999999999996,27.0,35.6,35.6,72.0 +35.64944444444444,-26.036111111111108,27.037499999999998,35.64944444444444,35.64944444444444,72.10000000000001 +35.69888888888889,-26.07222222222222,27.075,35.69888888888889,35.69888888888889,72.2 +35.748333333333335,-26.10833333333333,27.1125,35.748333333333335,35.748333333333335,72.3 +35.797777777777775,-26.144444444444442,27.15,35.797777777777775,35.797777777777775,72.4 +35.84722222222222,-26.180555555555554,27.1875,35.84722222222222,35.84722222222222,72.5 +35.89666666666667,-26.216666666666665,27.224999999999998,35.89666666666667,35.89666666666667,72.60000000000001 +35.94611111111111,-26.252777777777776,27.2625,35.94611111111111,35.94611111111111,72.7 +35.995555555555555,-26.288888888888888,27.3,35.995555555555555,35.995555555555555,72.8 +36.045,-26.325,27.3375,36.045,36.045,72.9 +36.09444444444444,-26.361111111111107,27.375,36.09444444444444,36.09444444444444,73.0 +36.14388888888889,-26.39722222222222,27.412499999999998,36.14388888888889,36.14388888888889,73.10000000000001 +36.193333333333335,-26.43333333333333,27.45,36.193333333333335,36.193333333333335,73.2 +36.242777777777775,-26.46944444444444,27.4875,36.242777777777775,36.242777777777775,73.3 +36.29222222222222,-26.505555555555553,27.525,36.29222222222222,36.29222222222222,73.4 +36.34166666666667,-26.541666666666664,27.5625,36.34166666666667,36.34166666666667,73.5 +36.39111111111111,-26.577777777777776,27.599999999999998,36.39111111111111,36.39111111111111,73.60000000000001 +36.440555555555555,-26.613888888888887,27.6375,36.440555555555555,36.440555555555555,73.7 +36.49,-26.65,27.675,36.49,36.49,73.8 +36.53944444444444,-26.68611111111111,27.7125,36.53944444444444,36.53944444444444,73.9 +36.58888888888889,-26.72222222222222,27.75,36.58888888888889,36.58888888888889,74.0 +36.638333333333335,-26.75833333333333,27.787499999999998,36.638333333333335,36.638333333333335,74.10000000000001 +36.687777777777775,-26.79444444444444,27.825,36.687777777777775,36.687777777777775,74.2 +36.73722222222222,-26.830555555555552,27.8625,36.73722222222222,36.73722222222222,74.3 +36.78666666666667,-26.866666666666664,27.9,36.78666666666667,36.78666666666667,74.4 +36.83611111111111,-26.902777777777775,27.9375,36.83611111111111,36.83611111111111,74.5 +36.885555555555555,-26.938888888888886,27.974999999999998,36.885555555555555,36.885555555555555,74.60000000000001 +36.935,-26.974999999999998,28.0125,36.935,36.935,74.7 +36.98444444444444,-27.01111111111111,28.05,36.98444444444444,36.98444444444444,74.8 +37.03388888888889,-27.04722222222222,28.0875,37.03388888888889,37.03388888888889,74.9 +37.083333333333336,-27.083333333333332,28.125,37.083333333333336,37.083333333333336,75.0 +37.132777777777775,-27.119444444444444,28.162499999999998,37.132777777777775,37.132777777777775,75.10000000000001 +37.18222222222222,-27.15555555555555,28.2,37.18222222222222,37.18222222222222,75.2 +37.23166666666667,-27.191666666666663,28.2375,37.23166666666667,37.23166666666667,75.3 +37.28111111111111,-27.227777777777774,28.275,37.28111111111111,37.28111111111111,75.4 +37.330555555555556,-27.263888888888886,28.3125,37.330555555555556,37.330555555555556,75.5 +37.38,-27.299999999999997,28.349999999999998,37.38,37.38,75.60000000000001 +37.42944444444444,-27.33611111111111,28.3875,37.42944444444444,37.42944444444444,75.7 +37.47888888888889,-27.37222222222222,28.425,37.47888888888889,37.47888888888889,75.8 +37.528333333333336,-27.40833333333333,28.4625,37.528333333333336,37.528333333333336,75.9 +37.577777777777776,-27.444444444444443,28.5,37.577777777777776,37.577777777777776,76.0 +37.62722222222222,-27.480555555555554,28.537499999999998,37.62722222222222,37.62722222222222,76.10000000000001 +37.67666666666667,-27.516666666666666,28.575,37.67666666666667,37.67666666666667,76.2 +37.72611111111111,-27.552777777777774,28.6125,37.72611111111111,37.72611111111111,76.3 +37.775555555555556,-27.588888888888885,28.65,37.775555555555556,37.775555555555556,76.4 +37.825,-27.624999999999996,28.6875,37.825,37.825,76.5 +37.87444444444444,-27.661111111111108,28.724999999999998,37.87444444444444,37.87444444444444,76.60000000000001 +37.92388888888889,-27.69722222222222,28.7625,37.92388888888889,37.92388888888889,76.7 +37.97333333333333,-27.73333333333333,28.799999999999997,37.97333333333333,37.97333333333333,76.80000000000001 +38.022777777777776,-27.769444444444442,28.8375,38.022777777777776,38.022777777777776,76.9 +38.07222222222222,-27.805555555555554,28.875,38.07222222222222,38.07222222222222,77.0 +38.12166666666666,-27.841666666666665,28.912499999999998,38.12166666666666,38.12166666666666,77.10000000000001 +38.17111111111111,-27.877777777777776,28.95,38.17111111111111,38.17111111111111,77.2 +38.220555555555556,-27.913888888888888,28.987499999999997,38.220555555555556,38.220555555555556,77.30000000000001 +38.269999999999996,-27.949999999999996,29.025,38.269999999999996,38.269999999999996,77.4 +38.31944444444444,-27.986111111111107,29.0625,38.31944444444444,38.31944444444444,77.5 +38.36888888888889,-28.02222222222222,29.099999999999998,38.36888888888889,38.36888888888889,77.60000000000001 +38.41833333333333,-28.05833333333333,29.1375,38.41833333333333,38.41833333333333,77.7 +38.467777777777776,-28.09444444444444,29.174999999999997,38.467777777777776,38.467777777777776,77.80000000000001 +38.51722222222222,-28.130555555555553,29.2125,38.51722222222222,38.51722222222222,77.9 +38.56666666666666,-28.166666666666664,29.25,38.56666666666666,38.56666666666666,78.0 +38.61611111111111,-28.202777777777776,29.287499999999998,38.61611111111111,38.61611111111111,78.10000000000001 +38.66555555555556,-28.238888888888887,29.325,38.66555555555556,38.66555555555556,78.2 +38.714999999999996,-28.275,29.362499999999997,38.714999999999996,38.714999999999996,78.30000000000001 +38.76444444444444,-28.31111111111111,29.4,38.76444444444444,38.76444444444444,78.4 +38.81388888888889,-28.347222222222218,29.4375,38.81388888888889,38.81388888888889,78.5 +38.86333333333333,-28.38333333333333,29.474999999999998,38.86333333333333,38.86333333333333,78.60000000000001 +38.91277777777778,-28.41944444444444,29.5125,38.91277777777778,38.91277777777778,78.7 +38.96222222222222,-28.455555555555552,29.549999999999997,38.96222222222222,38.96222222222222,78.80000000000001 +39.01166666666666,-28.491666666666664,29.5875,39.01166666666666,39.01166666666666,78.9 +39.06111111111111,-28.527777777777775,29.625,39.06111111111111,39.06111111111111,79.0 +39.11055555555556,-28.563888888888886,29.662499999999998,39.11055555555556,39.11055555555556,79.10000000000001 +39.16,-28.599999999999998,29.7,39.16,39.16,79.2 +39.20944444444444,-28.63611111111111,29.737499999999997,39.20944444444444,39.20944444444444,79.30000000000001 +39.25888888888889,-28.67222222222222,29.775,39.25888888888889,39.25888888888889,79.4 +39.30833333333333,-28.708333333333332,29.8125,39.30833333333333,39.30833333333333,79.5 +39.35777777777778,-28.74444444444444,29.849999999999998,39.35777777777778,39.35777777777778,79.60000000000001 +39.407222222222224,-28.78055555555555,29.8875,39.407222222222224,39.407222222222224,79.7 +39.45666666666666,-28.816666666666663,29.924999999999997,39.45666666666666,39.45666666666666,79.80000000000001 +39.50611111111111,-28.852777777777774,29.9625,39.50611111111111,39.50611111111111,79.9 +39.55555555555556,-28.888888888888886,30.0,39.55555555555556,39.55555555555556,80.0 +39.605,-28.924999999999997,30.037499999999998,39.605,39.605,80.10000000000001 +39.654444444444444,-28.96111111111111,30.075,39.654444444444444,39.654444444444444,80.2 +39.70388888888889,-28.99722222222222,30.112499999999997,39.70388888888889,39.70388888888889,80.30000000000001 +39.75333333333333,-29.03333333333333,30.15,39.75333333333333,39.75333333333333,80.4 +39.80277777777778,-29.069444444444443,30.1875,39.80277777777778,39.80277777777778,80.5 +39.852222222222224,-29.105555555555554,30.224999999999998,39.852222222222224,39.852222222222224,80.60000000000001 +39.901666666666664,-29.141666666666662,30.2625,39.901666666666664,39.901666666666664,80.7 +39.95111111111111,-29.177777777777774,30.299999999999997,39.95111111111111,39.95111111111111,80.80000000000001 +40.00055555555556,-29.213888888888885,30.3375,40.00055555555556,40.00055555555556,80.9 +40.05,-29.249999999999996,30.375,40.05,40.05,81.0 +40.099444444444444,-29.286111111111108,30.412499999999998,40.099444444444444,40.099444444444444,81.10000000000001 +40.14888888888889,-29.32222222222222,30.45,40.14888888888889,40.14888888888889,81.2 +40.19833333333333,-29.35833333333333,30.487499999999997,40.19833333333333,40.19833333333333,81.30000000000001 +40.24777777777778,-29.394444444444442,30.525,40.24777777777778,40.24777777777778,81.4 +40.297222222222224,-29.430555555555554,30.5625,40.297222222222224,40.297222222222224,81.5 +40.346666666666664,-29.466666666666665,30.599999999999998,40.346666666666664,40.346666666666664,81.60000000000001 +40.39611111111111,-29.502777777777776,30.6375,40.39611111111111,40.39611111111111,81.7 +40.44555555555556,-29.538888888888888,30.674999999999997,40.44555555555556,40.44555555555556,81.80000000000001 +40.495,-29.574999999999996,30.7125,40.495,40.495,81.9 +40.544444444444444,-29.611111111111107,30.75,40.544444444444444,40.544444444444444,82.0 +40.59388888888889,-29.64722222222222,30.787499999999998,40.59388888888889,40.59388888888889,82.10000000000001 +40.64333333333333,-29.68333333333333,30.825,40.64333333333333,40.64333333333333,82.2 +40.69277777777778,-29.71944444444444,30.862499999999997,40.69277777777778,40.69277777777778,82.30000000000001 +40.742222222222225,-29.755555555555553,30.9,40.742222222222225,40.742222222222225,82.4 +40.791666666666664,-29.791666666666664,30.9375,40.791666666666664,40.791666666666664,82.5 +40.84111111111111,-29.827777777777776,30.974999999999998,40.84111111111111,40.84111111111111,82.60000000000001 +40.89055555555556,-29.863888888888887,31.0125,40.89055555555556,40.89055555555556,82.7 +40.94,-29.9,31.049999999999997,40.94,40.94,82.80000000000001 +40.989444444444445,-29.93611111111111,31.0875,40.989444444444445,40.989444444444445,82.9 +41.03888888888889,-29.972222222222218,31.125,41.03888888888889,41.03888888888889,83.0 +41.08833333333333,-30.00833333333333,31.162499999999998,41.08833333333333,41.08833333333333,83.10000000000001 +41.13777777777778,-30.04444444444444,31.2,41.13777777777778,41.13777777777778,83.2 +41.187222222222225,-30.080555555555552,31.237499999999997,41.187222222222225,41.187222222222225,83.30000000000001 +41.236666666666665,-30.116666666666664,31.275,41.236666666666665,41.236666666666665,83.4 +41.28611111111111,-30.152777777777775,31.3125,41.28611111111111,41.28611111111111,83.5 +41.33555555555556,-30.188888888888886,31.349999999999998,41.33555555555556,41.33555555555556,83.60000000000001 +41.385,-30.224999999999998,31.3875,41.385,41.385,83.7 +41.434444444444445,-30.26111111111111,31.424999999999997,41.434444444444445,41.434444444444445,83.80000000000001 +41.48388888888889,-30.29722222222222,31.4625,41.48388888888889,41.48388888888889,83.9 +41.53333333333333,-30.333333333333332,31.5,41.53333333333333,41.53333333333333,84.0 +41.58277777777778,-30.36944444444444,31.537499999999998,41.58277777777778,41.58277777777778,84.10000000000001 +41.63222222222222,-30.40555555555555,31.575,41.63222222222222,41.63222222222222,84.2 +41.681666666666665,-30.441666666666663,31.612499999999997,41.681666666666665,41.681666666666665,84.30000000000001 +41.73111111111111,-30.477777777777774,31.65,41.73111111111111,41.73111111111111,84.4 +41.78055555555555,-30.513888888888886,31.6875,41.78055555555555,41.78055555555555,84.5 +41.83,-30.549999999999997,31.724999999999998,41.83,41.83,84.60000000000001 +41.879444444444445,-30.58611111111111,31.7625,41.879444444444445,41.879444444444445,84.7 +41.928888888888885,-30.62222222222222,31.799999999999997,41.928888888888885,41.928888888888885,84.80000000000001 +41.97833333333333,-30.65833333333333,31.8375,41.97833333333333,41.97833333333333,84.9 +42.02777777777778,-30.694444444444443,31.875,42.02777777777778,42.02777777777778,85.0 +42.07722222222222,-30.730555555555554,31.912499999999998,42.07722222222222,42.07722222222222,85.10000000000001 +42.126666666666665,-30.766666666666662,31.95,42.126666666666665,42.126666666666665,85.2 +42.17611111111111,-30.802777777777774,31.987499999999997,42.17611111111111,42.17611111111111,85.30000000000001 +42.22555555555555,-30.838888888888885,32.025,42.22555555555555,42.22555555555555,85.4 +42.275,-30.874999999999996,32.0625,42.275,42.275,85.5 +42.324444444444445,-30.911111111111108,32.1,42.324444444444445,42.324444444444445,85.60000000000001 +42.373888888888885,-30.94722222222222,32.137499999999996,42.373888888888885,42.373888888888885,85.7 +42.42333333333333,-30.98333333333333,32.175,42.42333333333333,42.42333333333333,85.80000000000001 +42.47277777777778,-31.019444444444442,32.2125,42.47277777777778,42.47277777777778,85.9 +42.52222222222222,-31.055555555555554,32.25,42.52222222222222,42.52222222222222,86.0 +42.571666666666665,-31.091666666666665,32.2875,42.571666666666665,42.571666666666665,86.10000000000001 +42.62111111111111,-31.127777777777776,32.324999999999996,42.62111111111111,42.62111111111111,86.2 +42.67055555555555,-31.163888888888884,32.3625,42.67055555555555,42.67055555555555,86.30000000000001 +42.72,-31.199999999999996,32.4,42.72,42.72,86.4 +42.769444444444446,-31.236111111111107,32.4375,42.769444444444446,42.769444444444446,86.5 +42.818888888888885,-31.27222222222222,32.475,42.818888888888885,42.818888888888885,86.60000000000001 +42.86833333333333,-31.30833333333333,32.512499999999996,42.86833333333333,42.86833333333333,86.7 +42.91777777777778,-31.34444444444444,32.55,42.91777777777778,42.91777777777778,86.80000000000001 +42.96722222222222,-31.380555555555553,32.5875,42.96722222222222,42.96722222222222,86.9 +43.016666666666666,-31.416666666666664,32.625,43.016666666666666,43.016666666666666,87.0 +43.06611111111111,-31.452777777777776,32.6625,43.06611111111111,43.06611111111111,87.10000000000001 +43.11555555555555,-31.488888888888887,32.699999999999996,43.11555555555555,43.11555555555555,87.2 +43.165,-31.525,32.7375,43.165,43.165,87.30000000000001 +43.214444444444446,-31.561111111111106,32.775,43.214444444444446,43.214444444444446,87.4 +43.263888888888886,-31.597222222222218,32.8125,43.263888888888886,43.263888888888886,87.5 +43.31333333333333,-31.63333333333333,32.85,43.31333333333333,43.31333333333333,87.60000000000001 +43.36277777777778,-31.66944444444444,32.887499999999996,43.36277777777778,43.36277777777778,87.7 +43.41222222222222,-31.705555555555552,32.925,43.41222222222222,43.41222222222222,87.80000000000001 +43.461666666666666,-31.741666666666664,32.9625,43.461666666666666,43.461666666666666,87.9 +43.51111111111111,-31.777777777777775,33.0,43.51111111111111,43.51111111111111,88.0 +43.56055555555555,-31.813888888888886,33.0375,43.56055555555555,43.56055555555555,88.10000000000001 +43.61,-31.849999999999998,33.074999999999996,43.61,43.61,88.2 +43.659444444444446,-31.88611111111111,33.1125,43.659444444444446,43.659444444444446,88.30000000000001 +43.708888888888886,-31.92222222222222,33.15,43.708888888888886,43.708888888888886,88.4 +43.75833333333333,-31.95833333333333,33.1875,43.75833333333333,43.75833333333333,88.5 +43.80777777777778,-31.99444444444444,33.225,43.80777777777778,43.80777777777778,88.60000000000001 +43.85722222222222,-32.03055555555555,33.262499999999996,43.85722222222222,43.85722222222222,88.7 +43.906666666666666,-32.06666666666666,33.3,43.906666666666666,43.906666666666666,88.80000000000001 +43.95611111111111,-32.102777777777774,33.3375,43.95611111111111,43.95611111111111,88.9 +44.00555555555555,-32.138888888888886,33.375,44.00555555555555,44.00555555555555,89.0 +44.055,-32.175,33.4125,44.055,44.055,89.10000000000001 +44.10444444444445,-32.21111111111111,33.449999999999996,44.10444444444445,44.10444444444445,89.2 +44.153888888888886,-32.24722222222222,33.4875,44.153888888888886,44.153888888888886,89.30000000000001 +44.20333333333333,-32.28333333333333,33.525,44.20333333333333,44.20333333333333,89.4 +44.25277777777778,-32.31944444444444,33.5625,44.25277777777778,44.25277777777778,89.5 +44.30222222222222,-32.355555555555554,33.6,44.30222222222222,44.30222222222222,89.60000000000001 +44.35166666666667,-32.391666666666666,33.637499999999996,44.35166666666667,44.35166666666667,89.7 +44.40111111111111,-32.42777777777778,33.675,44.40111111111111,44.40111111111111,89.80000000000001 +44.45055555555555,-32.46388888888889,33.7125,44.45055555555555,44.45055555555555,89.9 +44.5,-32.5,33.75,44.5,44.5,90.0 +44.54944444444445,-32.53611111111111,33.7875,44.54944444444445,44.54944444444445,90.10000000000001 +44.59888888888889,-32.572222222222216,33.824999999999996,44.59888888888889,44.59888888888889,90.2 +44.64833333333333,-32.60833333333333,33.8625,44.64833333333333,44.64833333333333,90.30000000000001 +44.69777777777778,-32.64444444444444,33.9,44.69777777777778,44.69777777777778,90.4 +44.74722222222222,-32.68055555555555,33.9375,44.74722222222222,44.74722222222222,90.5 +44.79666666666667,-32.71666666666666,33.975,44.79666666666667,44.79666666666667,90.60000000000001 +44.846111111111114,-32.75277777777777,34.012499999999996,44.846111111111114,44.846111111111114,90.7 +44.89555555555555,-32.788888888888884,34.05,44.89555555555555,44.89555555555555,90.80000000000001 +44.945,-32.824999999999996,34.0875,44.945,44.945,90.9 +44.99444444444445,-32.86111111111111,34.125,44.99444444444445,44.99444444444445,91.0 +45.04388888888889,-32.89722222222222,34.1625,45.04388888888889,45.04388888888889,91.10000000000001 +45.093333333333334,-32.93333333333333,34.199999999999996,45.093333333333334,45.093333333333334,91.2 +45.14277777777778,-32.96944444444444,34.2375,45.14277777777778,45.14277777777778,91.30000000000001 +45.19222222222222,-33.00555555555555,34.275,45.19222222222222,45.19222222222222,91.4 +45.24166666666667,-33.041666666666664,34.3125,45.24166666666667,45.24166666666667,91.5 +45.29111111111111,-33.077777777777776,34.35,45.29111111111111,45.29111111111111,91.60000000000001 +45.340555555555554,-33.11388888888889,34.387499999999996,45.340555555555554,45.340555555555554,91.7 +45.39,-33.15,34.425,45.39,45.39,91.80000000000001 +45.43944444444444,-33.18611111111111,34.4625,45.43944444444444,45.43944444444444,91.9 +45.48888888888889,-33.22222222222222,34.5,45.48888888888889,45.48888888888889,92.0 +45.538333333333334,-33.25833333333333,34.5375,45.538333333333334,45.538333333333334,92.10000000000001 +45.587777777777774,-33.294444444444444,34.574999999999996,45.587777777777774,45.587777777777774,92.2 +45.63722222222222,-33.330555555555556,34.6125,45.63722222222222,45.63722222222222,92.30000000000001 +45.68666666666667,-33.36666666666666,34.65,45.68666666666667,45.68666666666667,92.4 +45.73611111111111,-33.40277777777777,34.6875,45.73611111111111,45.73611111111111,92.5 +45.785555555555554,-33.43888888888888,34.725,45.785555555555554,45.785555555555554,92.60000000000001 +45.835,-33.474999999999994,34.762499999999996,45.835,45.835,92.7 +45.88444444444444,-33.511111111111106,34.8,45.88444444444444,45.88444444444444,92.80000000000001 +45.93388888888889,-33.54722222222222,34.8375,45.93388888888889,45.93388888888889,92.9 +45.983333333333334,-33.58333333333333,34.875,45.983333333333334,45.983333333333334,93.0 +46.032777777777774,-33.61944444444444,34.9125,46.032777777777774,46.032777777777774,93.10000000000001 +46.08222222222222,-33.65555555555555,34.949999999999996,46.08222222222222,46.08222222222222,93.2 +46.13166666666667,-33.69166666666666,34.9875,46.13166666666667,46.13166666666667,93.30000000000001 +46.18111111111111,-33.727777777777774,35.025,46.18111111111111,46.18111111111111,93.4 +46.230555555555554,-33.763888888888886,35.0625,46.230555555555554,46.230555555555554,93.5 +46.28,-33.8,35.1,46.28,46.28,93.60000000000001 +46.32944444444444,-33.83611111111111,35.137499999999996,46.32944444444444,46.32944444444444,93.7 +46.37888888888889,-33.87222222222222,35.175,46.37888888888889,46.37888888888889,93.80000000000001 +46.428333333333335,-33.90833333333333,35.2125,46.428333333333335,46.428333333333335,93.9 +46.477777777777774,-33.94444444444444,35.25,46.477777777777774,46.477777777777774,94.0 +46.52722222222222,-33.980555555555554,35.2875,46.52722222222222,46.52722222222222,94.10000000000001 +46.57666666666667,-34.016666666666666,35.324999999999996,46.57666666666667,46.57666666666667,94.2 +46.62611111111111,-34.05277777777778,35.3625,46.62611111111111,46.62611111111111,94.30000000000001 +46.675555555555555,-34.08888888888889,35.4,46.675555555555555,46.675555555555555,94.4 +46.725,-34.125,35.4375,46.725,46.725,94.5 +46.77444444444444,-34.16111111111111,35.475,46.77444444444444,46.77444444444444,94.60000000000001 +46.82388888888889,-34.197222222222216,35.512499999999996,46.82388888888889,46.82388888888889,94.7 +46.873333333333335,-34.23333333333333,35.55,46.873333333333335,46.873333333333335,94.80000000000001 +46.922777777777775,-34.26944444444444,35.5875,46.922777777777775,46.922777777777775,94.9 +46.97222222222222,-34.30555555555555,35.625,46.97222222222222,46.97222222222222,95.0 +47.02166666666667,-34.34166666666666,35.6625,47.02166666666667,47.02166666666667,95.10000000000001 +47.07111111111111,-34.37777777777777,35.699999999999996,47.07111111111111,47.07111111111111,95.2 +47.120555555555555,-34.413888888888884,35.7375,47.120555555555555,47.120555555555555,95.30000000000001 +47.17,-34.449999999999996,35.775,47.17,47.17,95.4 +47.21944444444444,-34.48611111111111,35.8125,47.21944444444444,47.21944444444444,95.5 +47.26888888888889,-34.52222222222222,35.85,47.26888888888889,47.26888888888889,95.60000000000001 +47.318333333333335,-34.55833333333333,35.887499999999996,47.318333333333335,47.318333333333335,95.7 +47.367777777777775,-34.59444444444444,35.925,47.367777777777775,47.367777777777775,95.80000000000001 +47.41722222222222,-34.63055555555555,35.9625,47.41722222222222,47.41722222222222,95.9 +47.46666666666667,-34.666666666666664,36.0,47.46666666666667,47.46666666666667,96.0 +47.51611111111111,-34.702777777777776,36.0375,47.51611111111111,47.51611111111111,96.10000000000001 +47.565555555555555,-34.73888888888889,36.074999999999996,47.565555555555555,47.565555555555555,96.2 +47.615,-34.775,36.1125,47.615,47.615,96.30000000000001 +47.66444444444444,-34.81111111111111,36.15,47.66444444444444,47.66444444444444,96.4 +47.71388888888889,-34.84722222222222,36.1875,47.71388888888889,47.71388888888889,96.5 +47.763333333333335,-34.88333333333333,36.225,47.763333333333335,47.763333333333335,96.60000000000001 +47.812777777777775,-34.919444444444444,36.262499999999996,47.812777777777775,47.812777777777775,96.7 +47.86222222222222,-34.955555555555556,36.3,47.86222222222222,47.86222222222222,96.80000000000001 +47.91166666666667,-34.99166666666666,36.3375,47.91166666666667,47.91166666666667,96.9 +47.96111111111111,-35.02777777777777,36.375,47.96111111111111,47.96111111111111,97.0 +48.010555555555555,-35.06388888888888,36.4125,48.010555555555555,48.010555555555555,97.10000000000001 +48.06,-35.099999999999994,36.449999999999996,48.06,48.06,97.2 +48.10944444444444,-35.136111111111106,36.4875,48.10944444444444,48.10944444444444,97.30000000000001 +48.15888888888889,-35.17222222222222,36.525,48.15888888888889,48.15888888888889,97.4 +48.208333333333336,-35.20833333333333,36.5625,48.208333333333336,48.208333333333336,97.5 +48.257777777777775,-35.24444444444444,36.6,48.257777777777775,48.257777777777775,97.60000000000001 +48.30722222222222,-35.28055555555555,36.637499999999996,48.30722222222222,48.30722222222222,97.7 +48.35666666666667,-35.31666666666666,36.675,48.35666666666667,48.35666666666667,97.80000000000001 +48.40611111111111,-35.352777777777774,36.7125,48.40611111111111,48.40611111111111,97.9 +48.455555555555556,-35.388888888888886,36.75,48.455555555555556,48.455555555555556,98.0 +48.505,-35.425,36.7875,48.505,48.505,98.10000000000001 +48.55444444444444,-35.46111111111111,36.824999999999996,48.55444444444444,48.55444444444444,98.2 +48.60388888888889,-35.49722222222222,36.8625,48.60388888888889,48.60388888888889,98.30000000000001 +48.653333333333336,-35.53333333333333,36.9,48.653333333333336,48.653333333333336,98.4 +48.702777777777776,-35.56944444444444,36.9375,48.702777777777776,48.702777777777776,98.5 +48.75222222222222,-35.605555555555554,36.975,48.75222222222222,48.75222222222222,98.60000000000001 +48.80166666666667,-35.641666666666666,37.012499999999996,48.80166666666667,48.80166666666667,98.7 +48.85111111111111,-35.67777777777778,37.05,48.85111111111111,48.85111111111111,98.80000000000001 +48.900555555555556,-35.71388888888889,37.0875,48.900555555555556,48.900555555555556,98.9 +48.949999999999996,-35.75,37.125,48.949999999999996,48.949999999999996,99.0 +48.99944444444444,-35.786111111111104,37.1625,48.99944444444444,48.99944444444444,99.10000000000001 +49.04888888888889,-35.822222222222216,37.199999999999996,49.04888888888889,49.04888888888889,99.2 +49.09833333333333,-35.85833333333333,37.2375,49.09833333333333,49.09833333333333,99.30000000000001 +49.147777777777776,-35.89444444444444,37.275,49.147777777777776,49.147777777777776,99.4 +49.19722222222222,-35.93055555555555,37.3125,49.19722222222222,49.19722222222222,99.5 +49.24666666666666,-35.96666666666666,37.35,49.24666666666666,49.24666666666666,99.60000000000001 +49.29611111111111,-36.00277777777777,37.387499999999996,49.29611111111111,49.29611111111111,99.7 +49.345555555555556,-36.038888888888884,37.425,49.345555555555556,49.345555555555556,99.80000000000001 +49.394999999999996,-36.074999999999996,37.4625,49.394999999999996,49.394999999999996,99.9 +49.44444444444444,-36.11111111111111,37.5,49.44444444444444,49.44444444444444,100.0 +49.49388888888889,-36.14722222222222,37.5375,49.49388888888889,49.49388888888889,100.10000000000001 +49.54333333333333,-36.18333333333333,37.574999999999996,49.54333333333333,49.54333333333333,100.2 +49.592777777777776,-36.21944444444444,37.6125,49.592777777777776,49.592777777777776,100.30000000000001 +49.64222222222222,-36.25555555555555,37.65,49.64222222222222,49.64222222222222,100.4 +49.69166666666666,-36.291666666666664,37.6875,49.69166666666666,49.69166666666666,100.5 +49.74111111111111,-36.327777777777776,37.725,49.74111111111111,49.74111111111111,100.60000000000001 +49.79055555555556,-36.36388888888889,37.762499999999996,49.79055555555556,49.79055555555556,100.7 +49.839999999999996,-36.4,37.8,49.839999999999996,49.839999999999996,100.80000000000001 +49.88944444444444,-36.43611111111111,37.8375,49.88944444444444,49.88944444444444,100.9 +49.93888888888889,-36.47222222222222,37.875,49.93888888888889,49.93888888888889,101.0 +49.98833333333333,-36.50833333333333,37.9125,49.98833333333333,49.98833333333333,101.10000000000001 +50.03777777777778,-36.544444444444444,37.949999999999996,50.03777777777778,50.03777777777778,101.2 +50.08722222222222,-36.58055555555555,37.9875,50.08722222222222,50.08722222222222,101.30000000000001 +50.13666666666666,-36.61666666666666,38.025,50.13666666666666,50.13666666666666,101.4 +50.18611111111111,-36.65277777777777,38.0625,50.18611111111111,50.18611111111111,101.5 +50.23555555555556,-36.68888888888888,38.1,50.23555555555556,50.23555555555556,101.60000000000001 +50.285,-36.724999999999994,38.137499999999996,50.285,50.285,101.7 +50.33444444444444,-36.761111111111106,38.175,50.33444444444444,50.33444444444444,101.80000000000001 +50.38388888888889,-36.79722222222222,38.2125,50.38388888888889,50.38388888888889,101.9 +50.43333333333333,-36.83333333333333,38.25,50.43333333333333,50.43333333333333,102.0 +50.48277777777778,-36.86944444444444,38.2875,50.48277777777778,50.48277777777778,102.10000000000001 +50.532222222222224,-36.90555555555555,38.324999999999996,50.532222222222224,50.532222222222224,102.2 +50.58166666666666,-36.94166666666666,38.3625,50.58166666666666,50.58166666666666,102.30000000000001 +50.63111111111111,-36.977777777777774,38.4,50.63111111111111,50.63111111111111,102.4 +50.68055555555556,-37.013888888888886,38.4375,50.68055555555556,50.68055555555556,102.5 +50.73,-37.05,38.475,50.73,50.73,102.60000000000001 +50.779444444444444,-37.08611111111111,38.512499999999996,50.779444444444444,50.779444444444444,102.7 +50.82888888888889,-37.12222222222222,38.55,50.82888888888889,50.82888888888889,102.80000000000001 +50.87833333333333,-37.15833333333333,38.5875,50.87833333333333,50.87833333333333,102.9 +50.92777777777778,-37.19444444444444,38.625,50.92777777777778,50.92777777777778,103.0 +50.977222222222224,-37.230555555555554,38.6625,50.977222222222224,50.977222222222224,103.10000000000001 +51.026666666666664,-37.266666666666666,38.699999999999996,51.026666666666664,51.026666666666664,103.2 +51.07611111111111,-37.30277777777778,38.7375,51.07611111111111,51.07611111111111,103.30000000000001 +51.12555555555556,-37.33888888888889,38.775,51.12555555555556,51.12555555555556,103.4 +51.175,-37.375,38.8125,51.175,51.175,103.5 +51.224444444444444,-37.411111111111104,38.85,51.224444444444444,51.224444444444444,103.60000000000001 +51.27388888888889,-37.447222222222216,38.887499999999996,51.27388888888889,51.27388888888889,103.7 +51.32333333333333,-37.48333333333333,38.925,51.32333333333333,51.32333333333333,103.80000000000001 +51.37277777777778,-37.51944444444444,38.9625,51.37277777777778,51.37277777777778,103.9 +51.422222222222224,-37.55555555555555,39.0,51.422222222222224,51.422222222222224,104.0 +51.471666666666664,-37.59166666666666,39.0375,51.471666666666664,51.471666666666664,104.10000000000001 +51.52111111111111,-37.62777777777777,39.074999999999996,51.52111111111111,51.52111111111111,104.2 +51.57055555555556,-37.663888888888884,39.1125,51.57055555555556,51.57055555555556,104.30000000000001 +51.62,-37.699999999999996,39.15,51.62,51.62,104.4 +51.669444444444444,-37.73611111111111,39.1875,51.669444444444444,51.669444444444444,104.5 +51.71888888888889,-37.77222222222222,39.225,51.71888888888889,51.71888888888889,104.60000000000001 +51.76833333333333,-37.80833333333333,39.262499999999996,51.76833333333333,51.76833333333333,104.7 +51.81777777777778,-37.84444444444444,39.3,51.81777777777778,51.81777777777778,104.80000000000001 +51.867222222222225,-37.88055555555555,39.3375,51.867222222222225,51.867222222222225,104.9 +51.916666666666664,-37.916666666666664,39.375,51.916666666666664,51.916666666666664,105.0 +51.96611111111111,-37.952777777777776,39.4125,51.96611111111111,51.96611111111111,105.10000000000001 +52.01555555555556,-37.98888888888889,39.449999999999996,52.01555555555556,52.01555555555556,105.2 +52.065,-38.025,39.4875,52.065,52.065,105.30000000000001 +52.114444444444445,-38.06111111111111,39.525,52.114444444444445,52.114444444444445,105.4 +52.16388888888889,-38.09722222222222,39.5625,52.16388888888889,52.16388888888889,105.5 +52.21333333333333,-38.13333333333333,39.6,52.21333333333333,52.21333333333333,105.60000000000001 +52.26277777777778,-38.169444444444444,39.637499999999996,52.26277777777778,52.26277777777778,105.7 +52.312222222222225,-38.20555555555555,39.675,52.312222222222225,52.312222222222225,105.80000000000001 +52.361666666666665,-38.24166666666666,39.7125,52.361666666666665,52.361666666666665,105.9 +52.41111111111111,-38.27777777777777,39.75,52.41111111111111,52.41111111111111,106.0 +52.46055555555555,-38.31388888888888,39.7875,52.46055555555555,52.46055555555555,106.10000000000001 +52.51,-38.349999999999994,39.824999999999996,52.51,52.51,106.2 +52.559444444444445,-38.386111111111106,39.8625,52.559444444444445,52.559444444444445,106.30000000000001 +52.608888888888885,-38.42222222222222,39.9,52.608888888888885,52.608888888888885,106.4 +52.65833333333333,-38.45833333333333,39.9375,52.65833333333333,52.65833333333333,106.5 +52.70777777777778,-38.49444444444444,39.975,52.70777777777778,52.70777777777778,106.60000000000001 +52.75722222222222,-38.53055555555555,40.012499999999996,52.75722222222222,52.75722222222222,106.7 +52.806666666666665,-38.56666666666666,40.05,52.806666666666665,52.806666666666665,106.80000000000001 +52.85611111111111,-38.602777777777774,40.0875,52.85611111111111,52.85611111111111,106.9 +52.90555555555555,-38.638888888888886,40.125,52.90555555555555,52.90555555555555,107.0 +52.955,-38.675,40.1625,52.955,52.955,107.10000000000001 +53.004444444444445,-38.71111111111111,40.199999999999996,53.004444444444445,53.004444444444445,107.2 +53.053888888888885,-38.74722222222222,40.2375,53.053888888888885,53.053888888888885,107.30000000000001 +53.10333333333333,-38.78333333333333,40.275,53.10333333333333,53.10333333333333,107.4 +53.15277777777778,-38.81944444444444,40.3125,53.15277777777778,53.15277777777778,107.5 +53.20222222222222,-38.855555555555554,40.35,53.20222222222222,53.20222222222222,107.60000000000001 +53.251666666666665,-38.891666666666666,40.387499999999996,53.251666666666665,53.251666666666665,107.7 +53.30111111111111,-38.92777777777778,40.425,53.30111111111111,53.30111111111111,107.80000000000001 +53.35055555555555,-38.96388888888889,40.4625,53.35055555555555,53.35055555555555,107.9 +53.4,-38.99999999999999,40.5,53.4,53.4,108.0 +53.449444444444445,-39.036111111111104,40.5375,53.449444444444445,53.449444444444445,108.10000000000001 +53.498888888888885,-39.072222222222216,40.574999999999996,53.498888888888885,53.498888888888885,108.2 +53.54833333333333,-39.10833333333333,40.6125,53.54833333333333,53.54833333333333,108.30000000000001 +53.59777777777778,-39.14444444444444,40.65,53.59777777777778,53.59777777777778,108.4 +53.64722222222222,-39.18055555555555,40.6875,53.64722222222222,53.64722222222222,108.5 +53.696666666666665,-39.21666666666666,40.725,53.696666666666665,53.696666666666665,108.60000000000001 +53.74611111111111,-39.25277777777777,40.762499999999996,53.74611111111111,53.74611111111111,108.7 +53.79555555555555,-39.288888888888884,40.8,53.79555555555555,53.79555555555555,108.80000000000001 +53.845,-39.324999999999996,40.8375,53.845,53.845,108.9 +53.894444444444446,-39.36111111111111,40.875,53.894444444444446,53.894444444444446,109.0 +53.943888888888885,-39.39722222222222,40.9125,53.943888888888885,53.943888888888885,109.10000000000001 +53.99333333333333,-39.43333333333333,40.949999999999996,53.99333333333333,53.99333333333333,109.2 +54.04277777777778,-39.46944444444444,40.9875,54.04277777777778,54.04277777777778,109.30000000000001 +54.09222222222222,-39.50555555555555,41.025,54.09222222222222,54.09222222222222,109.4 +54.141666666666666,-39.541666666666664,41.0625,54.141666666666666,54.141666666666666,109.5 +54.19111111111111,-39.577777777777776,41.1,54.19111111111111,54.19111111111111,109.60000000000001 +54.24055555555555,-39.61388888888889,41.137499999999996,54.24055555555555,54.24055555555555,109.7 +54.29,-39.65,41.175,54.29,54.29,109.80000000000001 +54.339444444444446,-39.68611111111111,41.2125,54.339444444444446,54.339444444444446,109.9 +54.388888888888886,-39.72222222222222,41.25,54.388888888888886,54.388888888888886,110.0 +54.43833333333333,-39.75833333333333,41.2875,54.43833333333333,54.43833333333333,110.10000000000001 +54.48777777777778,-39.79444444444444,41.324999999999996,54.48777777777778,54.48777777777778,110.2 +54.53722222222222,-39.83055555555555,41.3625,54.53722222222222,54.53722222222222,110.30000000000001 +54.586666666666666,-39.86666666666666,41.4,54.586666666666666,54.586666666666666,110.4 +54.63611111111111,-39.90277777777777,41.4375,54.63611111111111,54.63611111111111,110.5 +54.68555555555555,-39.93888888888888,41.475,54.68555555555555,54.68555555555555,110.60000000000001 +54.735,-39.974999999999994,41.512499999999996,54.735,54.735,110.7 +54.784444444444446,-40.011111111111106,41.55,54.784444444444446,54.784444444444446,110.80000000000001 +54.833888888888886,-40.04722222222222,41.5875,54.833888888888886,54.833888888888886,110.9 +54.88333333333333,-40.08333333333333,41.625,54.88333333333333,54.88333333333333,111.0 +54.93277777777778,-40.11944444444444,41.6625,54.93277777777778,54.93277777777778,111.10000000000001 +54.98222222222222,-40.15555555555555,41.699999999999996,54.98222222222222,54.98222222222222,111.2 +55.031666666666666,-40.19166666666666,41.7375,55.031666666666666,55.031666666666666,111.30000000000001 +55.08111111111111,-40.227777777777774,41.775,55.08111111111111,55.08111111111111,111.4 +55.13055555555555,-40.263888888888886,41.8125,55.13055555555555,55.13055555555555,111.5 +55.18,-40.3,41.85,55.18,55.18,111.60000000000001 +55.22944444444445,-40.33611111111111,41.887499999999996,55.22944444444445,55.22944444444445,111.7 +55.278888888888886,-40.37222222222222,41.925,55.278888888888886,55.278888888888886,111.80000000000001 +55.32833333333333,-40.40833333333333,41.9625,55.32833333333333,55.32833333333333,111.9 +55.37777777777778,-40.44444444444444,42.0,55.37777777777778,55.37777777777778,112.0 +55.42722222222222,-40.480555555555554,42.0375,55.42722222222222,55.42722222222222,112.10000000000001 +55.47666666666667,-40.516666666666666,42.074999999999996,55.47666666666667,55.47666666666667,112.2 +55.52611111111111,-40.55277777777778,42.1125,55.52611111111111,55.52611111111111,112.30000000000001 +55.57555555555555,-40.58888888888889,42.15,55.57555555555555,55.57555555555555,112.4 +55.625,-40.62499999999999,42.1875,55.625,55.625,112.5 +55.67444444444445,-40.661111111111104,42.225,55.67444444444445,55.67444444444445,112.60000000000001 +55.72388888888889,-40.697222222222216,42.262499999999996,55.72388888888889,55.72388888888889,112.7 +55.77333333333333,-40.73333333333333,42.3,55.77333333333333,55.77333333333333,112.80000000000001 +55.82277777777778,-40.76944444444444,42.3375,55.82277777777778,55.82277777777778,112.9 +55.87222222222222,-40.80555555555555,42.375,55.87222222222222,55.87222222222222,113.0 +55.92166666666667,-40.84166666666666,42.4125,55.92166666666667,55.92166666666667,113.10000000000001 +55.971111111111114,-40.87777777777777,42.449999999999996,55.971111111111114,55.971111111111114,113.2 +56.02055555555555,-40.913888888888884,42.4875,56.02055555555555,56.02055555555555,113.30000000000001 +56.07,-40.949999999999996,42.525,56.07,56.07,113.4 +56.11944444444444,-40.98611111111111,42.5625,56.11944444444444,56.11944444444444,113.5 +56.16888888888889,-41.02222222222222,42.6,56.16888888888889,56.16888888888889,113.60000000000001 +56.218333333333334,-41.05833333333333,42.637499999999996,56.218333333333334,56.218333333333334,113.7 +56.26777777777777,-41.09444444444444,42.675,56.26777777777777,56.26777777777777,113.80000000000001 +56.31722222222222,-41.13055555555555,42.7125,56.31722222222222,56.31722222222222,113.9 +56.36666666666667,-41.166666666666664,42.75,56.36666666666667,56.36666666666667,114.0 +56.41611111111111,-41.202777777777776,42.7875,56.41611111111111,56.41611111111111,114.10000000000001 +56.465555555555554,-41.23888888888889,42.824999999999996,56.465555555555554,56.465555555555554,114.2 +56.515,-41.275,42.8625,56.515,56.515,114.30000000000001 +56.56444444444444,-41.31111111111111,42.9,56.56444444444444,56.56444444444444,114.4 +56.61388888888889,-41.34722222222222,42.9375,56.61388888888889,56.61388888888889,114.5 +56.663333333333334,-41.38333333333333,42.975,56.663333333333334,56.663333333333334,114.60000000000001 +56.712777777777774,-41.41944444444444,43.012499999999996,56.712777777777774,56.712777777777774,114.7 +56.76222222222222,-41.45555555555555,43.05,56.76222222222222,56.76222222222222,114.80000000000001 +56.81166666666667,-41.49166666666666,43.0875,56.81166666666667,56.81166666666667,114.9 +56.86111111111111,-41.52777777777777,43.125,56.86111111111111,56.86111111111111,115.0 +56.910555555555554,-41.56388888888888,43.1625,56.910555555555554,56.910555555555554,115.10000000000001 +56.96,-41.599999999999994,43.199999999999996,56.96,56.96,115.2 +57.00944444444444,-41.636111111111106,43.2375,57.00944444444444,57.00944444444444,115.30000000000001 +57.05888888888889,-41.67222222222222,43.275,57.05888888888889,57.05888888888889,115.4 +57.108333333333334,-41.70833333333333,43.3125,57.108333333333334,57.108333333333334,115.5 +57.157777777777774,-41.74444444444444,43.35,57.157777777777774,57.157777777777774,115.60000000000001 +57.20722222222222,-41.78055555555555,43.387499999999996,57.20722222222222,57.20722222222222,115.7 +57.25666666666667,-41.81666666666666,43.425,57.25666666666667,57.25666666666667,115.80000000000001 +57.30611111111111,-41.852777777777774,43.4625,57.30611111111111,57.30611111111111,115.9 +57.355555555555554,-41.888888888888886,43.5,57.355555555555554,57.355555555555554,116.0 +57.405,-41.925,43.5375,57.405,57.405,116.10000000000001 +57.45444444444444,-41.96111111111111,43.574999999999996,57.45444444444444,57.45444444444444,116.2 +57.50388888888889,-41.99722222222222,43.6125,57.50388888888889,57.50388888888889,116.30000000000001 +57.553333333333335,-42.03333333333333,43.65,57.553333333333335,57.553333333333335,116.4 +57.602777777777774,-42.06944444444444,43.6875,57.602777777777774,57.602777777777774,116.5 +57.65222222222222,-42.105555555555554,43.725,57.65222222222222,57.65222222222222,116.60000000000001 +57.70166666666667,-42.141666666666666,43.762499999999996,57.70166666666667,57.70166666666667,116.7 +57.75111111111111,-42.17777777777778,43.8,57.75111111111111,57.75111111111111,116.80000000000001 +57.800555555555555,-42.21388888888888,43.8375,57.800555555555555,57.800555555555555,116.9 +57.85,-42.24999999999999,43.875,57.85,57.85,117.0 +57.89944444444444,-42.286111111111104,43.9125,57.89944444444444,57.89944444444444,117.10000000000001 +57.94888888888889,-42.322222222222216,43.949999999999996,57.94888888888889,57.94888888888889,117.2 +57.998333333333335,-42.35833333333333,43.9875,57.998333333333335,57.998333333333335,117.30000000000001 +58.047777777777775,-42.39444444444444,44.025,58.047777777777775,58.047777777777775,117.4 +58.09722222222222,-42.43055555555555,44.0625,58.09722222222222,58.09722222222222,117.5 +58.14666666666667,-42.46666666666666,44.1,58.14666666666667,58.14666666666667,117.60000000000001 +58.19611111111111,-42.50277777777777,44.137499999999996,58.19611111111111,58.19611111111111,117.7 +58.245555555555555,-42.538888888888884,44.175,58.245555555555555,58.245555555555555,117.80000000000001 +58.295,-42.574999999999996,44.2125,58.295,58.295,117.9 +58.34444444444444,-42.61111111111111,44.25,58.34444444444444,58.34444444444444,118.0 +58.39388888888889,-42.64722222222222,44.2875,58.39388888888889,58.39388888888889,118.10000000000001 +58.443333333333335,-42.68333333333333,44.324999999999996,58.443333333333335,58.443333333333335,118.2 +58.492777777777775,-42.71944444444444,44.3625,58.492777777777775,58.492777777777775,118.30000000000001 +58.54222222222222,-42.75555555555555,44.4,58.54222222222222,58.54222222222222,118.4 +58.59166666666667,-42.791666666666664,44.4375,58.59166666666667,58.59166666666667,118.5 +58.64111111111111,-42.827777777777776,44.475,58.64111111111111,58.64111111111111,118.60000000000001 +58.690555555555555,-42.86388888888889,44.512499999999996,58.690555555555555,58.690555555555555,118.7 +58.74,-42.9,44.55,58.74,58.74,118.80000000000001 +58.78944444444444,-42.93611111111111,44.5875,58.78944444444444,58.78944444444444,118.9 +58.83888888888889,-42.97222222222222,44.625,58.83888888888889,58.83888888888889,119.0 +58.888333333333335,-43.008333333333326,44.6625,58.888333333333335,58.888333333333335,119.10000000000001 +58.937777777777775,-43.04444444444444,44.699999999999996,58.937777777777775,58.937777777777775,119.2 +58.98722222222222,-43.08055555555555,44.7375,58.98722222222222,58.98722222222222,119.30000000000001 +59.03666666666667,-43.11666666666666,44.775,59.03666666666667,59.03666666666667,119.4 +59.08611111111111,-43.15277777777777,44.8125,59.08611111111111,59.08611111111111,119.5 +59.135555555555555,-43.18888888888888,44.85,59.135555555555555,59.135555555555555,119.60000000000001 +59.185,-43.224999999999994,44.887499999999996,59.185,59.185,119.7 +59.23444444444444,-43.261111111111106,44.925,59.23444444444444,59.23444444444444,119.80000000000001 +59.28388888888889,-43.29722222222222,44.9625,59.28388888888889,59.28388888888889,119.9 +59.333333333333336,-43.33333333333333,45.0,59.333333333333336,59.333333333333336,120.0 +59.382777777777775,-43.36944444444444,45.0375,59.382777777777775,59.382777777777775,120.10000000000001 +59.43222222222222,-43.40555555555555,45.074999999999996,59.43222222222222,59.43222222222222,120.2 +59.48166666666667,-43.44166666666666,45.1125,59.48166666666667,59.48166666666667,120.30000000000001 +59.53111111111111,-43.477777777777774,45.15,59.53111111111111,59.53111111111111,120.4 +59.580555555555556,-43.513888888888886,45.1875,59.580555555555556,59.580555555555556,120.5 +59.63,-43.55,45.225,59.63,59.63,120.60000000000001 +59.67944444444444,-43.58611111111111,45.262499999999996,59.67944444444444,59.67944444444444,120.7 +59.72888888888889,-43.62222222222222,45.3,59.72888888888889,59.72888888888889,120.80000000000001 +59.77833333333333,-43.65833333333333,45.3375,59.77833333333333,59.77833333333333,120.9 +59.827777777777776,-43.69444444444444,45.375,59.827777777777776,59.827777777777776,121.0 +59.87722222222222,-43.730555555555554,45.4125,59.87722222222222,59.87722222222222,121.10000000000001 +59.92666666666666,-43.766666666666666,45.449999999999996,59.92666666666666,59.92666666666666,121.2 +59.97611111111111,-43.80277777777778,45.4875,59.97611111111111,59.97611111111111,121.30000000000001 +60.025555555555556,-43.83888888888888,45.525,60.025555555555556,60.025555555555556,121.4 +60.074999999999996,-43.87499999999999,45.5625,60.074999999999996,60.074999999999996,121.5 +60.12444444444444,-43.911111111111104,45.6,60.12444444444444,60.12444444444444,121.60000000000001 +60.17388888888889,-43.947222222222216,45.637499999999996,60.17388888888889,60.17388888888889,121.7 +60.22333333333333,-43.98333333333333,45.675,60.22333333333333,60.22333333333333,121.80000000000001 +60.272777777777776,-44.01944444444444,45.7125,60.272777777777776,60.272777777777776,121.9 +60.32222222222222,-44.05555555555555,45.75,60.32222222222222,60.32222222222222,122.0 +60.37166666666666,-44.09166666666666,45.7875,60.37166666666666,60.37166666666666,122.10000000000001 +60.42111111111111,-44.12777777777777,45.824999999999996,60.42111111111111,60.42111111111111,122.2 +60.470555555555556,-44.163888888888884,45.8625,60.470555555555556,60.470555555555556,122.30000000000001 +60.519999999999996,-44.199999999999996,45.9,60.519999999999996,60.519999999999996,122.4 +60.56944444444444,-44.23611111111111,45.9375,60.56944444444444,60.56944444444444,122.5 +60.61888888888889,-44.27222222222222,45.975,60.61888888888889,60.61888888888889,122.60000000000001 +60.66833333333333,-44.30833333333333,46.012499999999996,60.66833333333333,60.66833333333333,122.7 +60.717777777777776,-44.34444444444444,46.05,60.717777777777776,60.717777777777776,122.80000000000001 +60.76722222222222,-44.38055555555555,46.0875,60.76722222222222,60.76722222222222,122.9 +60.81666666666666,-44.416666666666664,46.125,60.81666666666666,60.81666666666666,123.0 +60.86611111111111,-44.452777777777776,46.1625,60.86611111111111,60.86611111111111,123.10000000000001 +60.91555555555556,-44.48888888888889,46.199999999999996,60.91555555555556,60.91555555555556,123.2 +60.964999999999996,-44.525,46.2375,60.964999999999996,60.964999999999996,123.30000000000001 +61.01444444444444,-44.56111111111111,46.275,61.01444444444444,61.01444444444444,123.4 +61.06388888888889,-44.59722222222222,46.3125,61.06388888888889,61.06388888888889,123.5 +61.11333333333333,-44.633333333333326,46.35,61.11333333333333,61.11333333333333,123.60000000000001 +61.16277777777778,-44.66944444444444,46.387499999999996,61.16277777777778,61.16277777777778,123.7 +61.21222222222222,-44.70555555555555,46.425,61.21222222222222,61.21222222222222,123.80000000000001 +61.26166666666666,-44.74166666666666,46.4625,61.26166666666666,61.26166666666666,123.9 +61.31111111111111,-44.77777777777777,46.5,61.31111111111111,61.31111111111111,124.0 +61.36055555555556,-44.81388888888888,46.5375,61.36055555555556,61.36055555555556,124.10000000000001 +61.41,-44.849999999999994,46.574999999999996,61.41,61.41,124.2 +61.45944444444444,-44.886111111111106,46.6125,61.45944444444444,61.45944444444444,124.30000000000001 +61.50888888888889,-44.92222222222222,46.65,61.50888888888889,61.50888888888889,124.4 +61.55833333333333,-44.95833333333333,46.6875,61.55833333333333,61.55833333333333,124.5 +61.60777777777778,-44.99444444444444,46.725,61.60777777777778,61.60777777777778,124.60000000000001 +61.657222222222224,-45.03055555555555,46.762499999999996,61.657222222222224,61.657222222222224,124.7 +61.70666666666666,-45.06666666666666,46.8,61.70666666666666,61.70666666666666,124.80000000000001 +61.75611111111111,-45.102777777777774,46.8375,61.75611111111111,61.75611111111111,124.9 +61.80555555555556,-45.138888888888886,46.875,61.80555555555556,61.80555555555556,125.0 +61.855,-45.175,46.9125,61.855,61.855,125.10000000000001 +61.904444444444444,-45.21111111111111,46.949999999999996,61.904444444444444,61.904444444444444,125.2 +61.95388888888889,-45.24722222222222,46.9875,61.95388888888889,61.95388888888889,125.30000000000001 +62.00333333333333,-45.28333333333333,47.025,62.00333333333333,62.00333333333333,125.4 +62.05277777777778,-45.31944444444444,47.0625,62.05277777777778,62.05277777777778,125.5 +62.102222222222224,-45.355555555555554,47.1,62.102222222222224,62.102222222222224,125.60000000000001 +62.151666666666664,-45.391666666666666,47.137499999999996,62.151666666666664,62.151666666666664,125.7 +62.20111111111111,-45.42777777777777,47.175,62.20111111111111,62.20111111111111,125.80000000000001 +62.25055555555556,-45.46388888888888,47.2125,62.25055555555556,62.25055555555556,125.9 +62.3,-45.49999999999999,47.25,62.3,62.3,126.0 +62.349444444444444,-45.536111111111104,47.2875,62.349444444444444,62.349444444444444,126.10000000000001 +62.39888888888889,-45.572222222222216,47.324999999999996,62.39888888888889,62.39888888888889,126.2 +62.44833333333333,-45.60833333333333,47.3625,62.44833333333333,62.44833333333333,126.30000000000001 +62.49777777777778,-45.64444444444444,47.4,62.49777777777778,62.49777777777778,126.4 +62.547222222222224,-45.68055555555555,47.4375,62.547222222222224,62.547222222222224,126.5 +62.596666666666664,-45.71666666666666,47.475,62.596666666666664,62.596666666666664,126.60000000000001 +62.64611111111111,-45.75277777777777,47.512499999999996,62.64611111111111,62.64611111111111,126.7 +62.69555555555556,-45.788888888888884,47.55,62.69555555555556,62.69555555555556,126.80000000000001 +62.745,-45.824999999999996,47.5875,62.745,62.745,126.9 +62.794444444444444,-45.86111111111111,47.625,62.794444444444444,62.794444444444444,127.0 +62.84388888888889,-45.89722222222222,47.6625,62.84388888888889,62.84388888888889,127.10000000000001 +62.89333333333333,-45.93333333333333,47.699999999999996,62.89333333333333,62.89333333333333,127.2 +62.94277777777778,-45.96944444444444,47.7375,62.94277777777778,62.94277777777778,127.30000000000001 +62.992222222222225,-46.00555555555555,47.775,62.992222222222225,62.992222222222225,127.4 +63.041666666666664,-46.041666666666664,47.8125,63.041666666666664,63.041666666666664,127.5 +63.09111111111111,-46.077777777777776,47.85,63.09111111111111,63.09111111111111,127.60000000000001 +63.14055555555556,-46.11388888888889,47.887499999999996,63.14055555555556,63.14055555555556,127.7 +63.19,-46.15,47.925,63.19,63.19,127.80000000000001 +63.239444444444445,-46.18611111111111,47.9625,63.239444444444445,63.239444444444445,127.9 +63.28888888888889,-46.222222222222214,48.0,63.28888888888889,63.28888888888889,128.0 +63.33833333333333,-46.258333333333326,48.0375,63.33833333333333,63.33833333333333,128.1 +63.38777777777778,-46.29444444444444,48.074999999999996,63.38777777777778,63.38777777777778,128.20000000000002 +63.43722222222222,-46.33055555555555,48.1125,63.43722222222222,63.43722222222222,128.3 +63.486666666666665,-46.36666666666666,48.15,63.486666666666665,63.486666666666665,128.4 +63.53611111111111,-46.40277777777777,48.1875,63.53611111111111,63.53611111111111,128.5 +63.58555555555555,-46.43888888888888,48.225,63.58555555555555,63.58555555555555,128.6 +63.635,-46.474999999999994,48.262499999999996,63.635,63.635,128.70000000000002 +63.684444444444445,-46.511111111111106,48.3,63.684444444444445,63.684444444444445,128.8 +63.733888888888885,-46.54722222222222,48.3375,63.733888888888885,63.733888888888885,128.9 +63.78333333333333,-46.58333333333333,48.375,63.78333333333333,63.78333333333333,129.0 +63.83277777777778,-46.61944444444444,48.4125,63.83277777777778,63.83277777777778,129.1 +63.88222222222222,-46.65555555555555,48.449999999999996,63.88222222222222,63.88222222222222,129.20000000000002 +63.931666666666665,-46.69166666666666,48.4875,63.931666666666665,63.931666666666665,129.3 +63.98111111111111,-46.727777777777774,48.525,63.98111111111111,63.98111111111111,129.4 +64.03055555555555,-46.763888888888886,48.5625,64.03055555555555,64.03055555555555,129.5 +64.08,-46.8,48.6,64.08,64.08,129.6 +64.12944444444445,-46.83611111111111,48.637499999999996,64.12944444444445,64.12944444444445,129.70000000000002 +64.17888888888889,-46.87222222222222,48.675,64.17888888888889,64.17888888888889,129.8 +64.22833333333334,-46.90833333333333,48.7125,64.22833333333334,64.22833333333334,129.9 +64.27777777777777,-46.94444444444444,48.75,64.27777777777777,64.27777777777777,130.0 +64.32722222222222,-46.980555555555554,48.7875,64.32722222222222,64.32722222222222,130.1 +64.37666666666667,-47.016666666666666,48.824999999999996,64.37666666666667,64.37666666666667,130.20000000000002 +64.42611111111111,-47.05277777777777,48.8625,64.42611111111111,64.42611111111111,130.3 +64.47555555555556,-47.08888888888888,48.9,64.47555555555556,64.47555555555556,130.4 +64.525,-47.12499999999999,48.9375,64.525,64.525,130.5 +64.57444444444444,-47.161111111111104,48.975,64.57444444444444,64.57444444444444,130.6 +64.62388888888889,-47.197222222222216,49.012499999999996,64.62388888888889,64.62388888888889,130.70000000000002 +64.67333333333333,-47.23333333333333,49.05,64.67333333333333,64.67333333333333,130.8 +64.72277777777778,-47.26944444444444,49.0875,64.72277777777778,64.72277777777778,130.9 +64.77222222222223,-47.30555555555555,49.125,64.77222222222223,64.77222222222223,131.0 +64.82166666666667,-47.34166666666666,49.1625,64.82166666666667,64.82166666666667,131.1 +64.8711111111111,-47.37777777777777,49.199999999999996,64.8711111111111,64.8711111111111,131.20000000000002 +64.92055555555555,-47.413888888888884,49.2375,64.92055555555555,64.92055555555555,131.3 +64.97,-47.449999999999996,49.275,64.97,64.97,131.4 +65.01944444444445,-47.48611111111111,49.3125,65.01944444444445,65.01944444444445,131.5 +65.06888888888889,-47.52222222222222,49.35,65.06888888888889,65.06888888888889,131.6 +65.11833333333333,-47.55833333333333,49.387499999999996,65.11833333333333,65.11833333333333,131.70000000000002 +65.16777777777777,-47.59444444444444,49.425,65.16777777777777,65.16777777777777,131.8 +65.21722222222222,-47.63055555555555,49.4625,65.21722222222222,65.21722222222222,131.9 +65.26666666666667,-47.666666666666664,49.5,65.26666666666667,65.26666666666667,132.0 +65.31611111111111,-47.702777777777776,49.5375,65.31611111111111,65.31611111111111,132.1 +65.36555555555556,-47.73888888888889,49.574999999999996,65.36555555555556,65.36555555555556,132.20000000000002 +65.41499999999999,-47.775,49.6125,65.41499999999999,65.41499999999999,132.3 +65.46444444444444,-47.81111111111111,49.65,65.46444444444444,65.46444444444444,132.4 +65.51388888888889,-47.847222222222214,49.6875,65.51388888888889,65.51388888888889,132.5 +65.56333333333333,-47.883333333333326,49.725,65.56333333333333,65.56333333333333,132.6 +65.61277777777778,-47.91944444444444,49.762499999999996,65.61277777777778,65.61277777777778,132.70000000000002 +65.66222222222223,-47.95555555555555,49.8,65.66222222222223,65.66222222222223,132.8 +65.71166666666666,-47.99166666666666,49.8375,65.71166666666666,65.71166666666666,132.9 +65.7611111111111,-48.02777777777777,49.875,65.7611111111111,65.7611111111111,133.0 +65.81055555555555,-48.06388888888888,49.9125,65.81055555555555,65.81055555555555,133.1 +65.86,-48.099999999999994,49.949999999999996,65.86,65.86,133.20000000000002 +65.90944444444445,-48.136111111111106,49.9875,65.90944444444445,65.90944444444445,133.3 +65.9588888888889,-48.17222222222222,50.025,65.9588888888889,65.9588888888889,133.4 +66.00833333333333,-48.20833333333333,50.0625,66.00833333333333,66.00833333333333,133.5 +66.05777777777777,-48.24444444444444,50.1,66.05777777777777,66.05777777777777,133.6 +66.10722222222222,-48.28055555555555,50.137499999999996,66.10722222222222,66.10722222222222,133.70000000000002 +66.15666666666667,-48.31666666666666,50.175,66.15666666666667,66.15666666666667,133.8 +66.20611111111111,-48.352777777777774,50.2125,66.20611111111111,66.20611111111111,133.9 +66.25555555555556,-48.388888888888886,50.25,66.25555555555556,66.25555555555556,134.0 +66.30499999999999,-48.425,50.2875,66.30499999999999,66.30499999999999,134.1 +66.35444444444444,-48.46111111111111,50.324999999999996,66.35444444444444,66.35444444444444,134.20000000000002 +66.40388888888889,-48.49722222222222,50.3625,66.40388888888889,66.40388888888889,134.3 +66.45333333333333,-48.53333333333333,50.4,66.45333333333333,66.45333333333333,134.4 +66.50277777777778,-48.56944444444444,50.4375,66.50277777777778,66.50277777777778,134.5 +66.55222222222223,-48.605555555555554,50.475,66.55222222222223,66.55222222222223,134.6 +66.60166666666666,-48.64166666666666,50.512499999999996,66.60166666666666,66.60166666666666,134.70000000000002 +66.6511111111111,-48.67777777777777,50.55,66.6511111111111,66.6511111111111,134.8 +66.70055555555555,-48.71388888888888,50.5875,66.70055555555555,66.70055555555555,134.9 +66.75,-48.74999999999999,50.625,66.75,66.75,135.0 +66.79944444444445,-48.786111111111104,50.6625,66.79944444444445,66.79944444444445,135.1 +66.8488888888889,-48.822222222222216,50.699999999999996,66.8488888888889,66.8488888888889,135.20000000000002 +66.89833333333333,-48.85833333333333,50.7375,66.89833333333333,66.89833333333333,135.3 +66.94777777777777,-48.89444444444444,50.775,66.94777777777777,66.94777777777777,135.4 +66.99722222222222,-48.93055555555555,50.8125,66.99722222222222,66.99722222222222,135.5 +67.04666666666667,-48.96666666666666,50.85,67.04666666666667,67.04666666666667,135.6 +67.09611111111111,-49.00277777777777,50.887499999999996,67.09611111111111,67.09611111111111,135.70000000000002 +67.14555555555556,-49.038888888888884,50.925,67.14555555555556,67.14555555555556,135.8 +67.195,-49.074999999999996,50.9625,67.195,67.195,135.9 +67.24444444444444,-49.11111111111111,51.0,67.24444444444444,67.24444444444444,136.0 +67.29388888888889,-49.14722222222222,51.0375,67.29388888888889,67.29388888888889,136.1 +67.34333333333333,-49.18333333333333,51.074999999999996,67.34333333333333,67.34333333333333,136.20000000000002 +67.39277777777778,-49.21944444444444,51.1125,67.39277777777778,67.39277777777778,136.3 +67.44222222222223,-49.25555555555555,51.15,67.44222222222223,67.44222222222223,136.4 +67.49166666666666,-49.291666666666664,51.1875,67.49166666666666,67.49166666666666,136.5 +67.5411111111111,-49.327777777777776,51.225,67.5411111111111,67.5411111111111,136.6 +67.59055555555555,-49.36388888888889,51.262499999999996,67.59055555555555,67.59055555555555,136.70000000000002 +67.64,-49.4,51.3,67.64,67.64,136.8 +67.68944444444445,-49.43611111111111,51.3375,67.68944444444445,67.68944444444445,136.9 +67.7388888888889,-49.472222222222214,51.375,67.7388888888889,67.7388888888889,137.0 +67.78833333333333,-49.508333333333326,51.4125,67.78833333333333,67.78833333333333,137.1 +67.83777777777777,-49.54444444444444,51.449999999999996,67.83777777777777,67.83777777777777,137.20000000000002 +67.88722222222222,-49.58055555555555,51.4875,67.88722222222222,67.88722222222222,137.3 +67.93666666666667,-49.61666666666666,51.525,67.93666666666667,67.93666666666667,137.4 +67.98611111111111,-49.65277777777777,51.5625,67.98611111111111,67.98611111111111,137.5 +68.03555555555556,-49.68888888888888,51.6,68.03555555555556,68.03555555555556,137.6 +68.085,-49.724999999999994,51.637499999999996,68.085,68.085,137.70000000000002 +68.13444444444444,-49.761111111111106,51.675,68.13444444444444,68.13444444444444,137.8 +68.18388888888889,-49.79722222222222,51.7125,68.18388888888889,68.18388888888889,137.9 +68.23333333333333,-49.83333333333333,51.75,68.23333333333333,68.23333333333333,138.0 +68.28277777777778,-49.86944444444444,51.7875,68.28277777777778,68.28277777777778,138.1 +68.33222222222223,-49.90555555555555,51.824999999999996,68.33222222222223,68.33222222222223,138.20000000000002 +68.38166666666666,-49.94166666666666,51.8625,68.38166666666666,68.38166666666666,138.3 +68.43111111111111,-49.977777777777774,51.9,68.43111111111111,68.43111111111111,138.4 +68.48055555555555,-50.013888888888886,51.9375,68.48055555555555,68.48055555555555,138.5 +68.53,-50.05,51.975,68.53,68.53,138.6 +68.57944444444445,-50.08611111111111,52.012499999999996,68.57944444444445,68.57944444444445,138.70000000000002 +68.6288888888889,-50.12222222222222,52.05,68.6288888888889,68.6288888888889,138.8 +68.67833333333333,-50.15833333333333,52.0875,68.67833333333333,68.67833333333333,138.9 +68.72777777777777,-50.19444444444444,52.125,68.72777777777777,68.72777777777777,139.0 +68.77722222222222,-50.230555555555554,52.1625,68.77722222222222,68.77722222222222,139.1 +68.82666666666667,-50.26666666666666,52.199999999999996,68.82666666666667,68.82666666666667,139.20000000000002 +68.87611111111111,-50.30277777777777,52.2375,68.87611111111111,68.87611111111111,139.3 +68.92555555555555,-50.33888888888888,52.275,68.92555555555555,68.92555555555555,139.4 +68.975,-50.37499999999999,52.3125,68.975,68.975,139.5 +69.02444444444444,-50.411111111111104,52.35,69.02444444444444,69.02444444444444,139.6 +69.07388888888889,-50.447222222222216,52.387499999999996,69.07388888888889,69.07388888888889,139.70000000000002 +69.12333333333333,-50.48333333333333,52.425,69.12333333333333,69.12333333333333,139.8 +69.17277777777778,-50.51944444444444,52.4625,69.17277777777778,69.17277777777778,139.9 +69.22222222222221,-50.55555555555555,52.5,69.22222222222221,69.22222222222221,140.0 +69.27166666666666,-50.59166666666666,52.5375,69.27166666666666,69.27166666666666,140.1 +69.32111111111111,-50.62777777777777,52.574999999999996,69.32111111111111,69.32111111111111,140.20000000000002 +69.37055555555555,-50.663888888888884,52.6125,69.37055555555555,69.37055555555555,140.3 +69.42,-50.699999999999996,52.65,69.42,69.42,140.4 +69.46944444444445,-50.73611111111111,52.6875,69.46944444444445,69.46944444444445,140.5 +69.51888888888888,-50.77222222222222,52.725,69.51888888888888,69.51888888888888,140.6 +69.56833333333333,-50.80833333333333,52.762499999999996,69.56833333333333,69.56833333333333,140.70000000000002 +69.61777777777777,-50.84444444444444,52.8,69.61777777777777,69.61777777777777,140.8 +69.66722222222222,-50.88055555555555,52.8375,69.66722222222222,69.66722222222222,140.9 +69.71666666666667,-50.916666666666664,52.875,69.71666666666667,69.71666666666667,141.0 +69.76611111111112,-50.952777777777776,52.9125,69.76611111111112,69.76611111111112,141.1 +69.81555555555555,-50.98888888888889,52.949999999999996,69.81555555555555,69.81555555555555,141.20000000000002 +69.865,-51.025,52.9875,69.865,69.865,141.3 +69.91444444444444,-51.0611111111111,53.025,69.91444444444444,69.91444444444444,141.4 +69.96388888888889,-51.097222222222214,53.0625,69.96388888888889,69.96388888888889,141.5 +70.01333333333334,-51.133333333333326,53.1,70.01333333333334,70.01333333333334,141.6 +70.06277777777778,-51.16944444444444,53.137499999999996,70.06277777777778,70.06277777777778,141.70000000000002 +70.11222222222221,-51.20555555555555,53.175,70.11222222222221,70.11222222222221,141.8 +70.16166666666666,-51.24166666666666,53.2125,70.16166666666666,70.16166666666666,141.9 +70.21111111111111,-51.27777777777777,53.25,70.21111111111111,70.21111111111111,142.0 +70.26055555555556,-51.31388888888888,53.2875,70.26055555555556,70.26055555555556,142.1 +70.31,-51.349999999999994,53.324999999999996,70.31,70.31,142.20000000000002 +70.35944444444445,-51.386111111111106,53.3625,70.35944444444445,70.35944444444445,142.3 +70.40888888888888,-51.42222222222222,53.4,70.40888888888888,70.40888888888888,142.4 +70.45833333333333,-51.45833333333333,53.4375,70.45833333333333,70.45833333333333,142.5 +70.50777777777778,-51.49444444444444,53.475,70.50777777777778,70.50777777777778,142.6 +70.55722222222222,-51.53055555555555,53.512499999999996,70.55722222222222,70.55722222222222,142.70000000000002 +70.60666666666667,-51.56666666666666,53.55,70.60666666666667,70.60666666666667,142.8 +70.65611111111112,-51.602777777777774,53.5875,70.65611111111112,70.65611111111112,142.9 +70.70555555555555,-51.638888888888886,53.625,70.70555555555555,70.70555555555555,143.0 +70.755,-51.675,53.6625,70.755,70.755,143.1 +70.80444444444444,-51.71111111111111,53.699999999999996,70.80444444444444,70.80444444444444,143.20000000000002 +70.85388888888889,-51.74722222222222,53.7375,70.85388888888889,70.85388888888889,143.3 +70.90333333333334,-51.78333333333333,53.775,70.90333333333334,70.90333333333334,143.4 +70.95277777777778,-51.81944444444444,53.8125,70.95277777777778,70.95277777777778,143.5 +71.00222222222222,-51.85555555555555,53.85,71.00222222222222,71.00222222222222,143.6 +71.05166666666666,-51.89166666666666,53.887499999999996,71.05166666666666,71.05166666666666,143.70000000000002 +71.10111111111111,-51.92777777777777,53.925,71.10111111111111,71.10111111111111,143.8 +71.15055555555556,-51.96388888888888,53.9625,71.15055555555556,71.15055555555556,143.9 +71.2,-51.99999999999999,54.0,71.2,71.2,144.0 +71.24944444444445,-52.036111111111104,54.0375,71.24944444444445,71.24944444444445,144.1 +71.29888888888888,-52.072222222222216,54.074999999999996,71.29888888888888,71.29888888888888,144.20000000000002 +71.34833333333333,-52.10833333333333,54.1125,71.34833333333333,71.34833333333333,144.3 +71.39777777777778,-52.14444444444444,54.15,71.39777777777778,71.39777777777778,144.4 +71.44722222222222,-52.18055555555555,54.1875,71.44722222222222,71.44722222222222,144.5 +71.49666666666667,-52.21666666666666,54.225,71.49666666666667,71.49666666666667,144.6 +71.54611111111112,-52.25277777777777,54.262499999999996,71.54611111111112,71.54611111111112,144.70000000000002 +71.59555555555555,-52.288888888888884,54.3,71.59555555555555,71.59555555555555,144.8 +71.645,-52.324999999999996,54.3375,71.645,71.645,144.9 +71.69444444444444,-52.36111111111111,54.375,71.69444444444444,71.69444444444444,145.0 +71.74388888888889,-52.39722222222222,54.4125,71.74388888888889,71.74388888888889,145.1 +71.79333333333334,-52.43333333333333,54.449999999999996,71.79333333333334,71.79333333333334,145.20000000000002 +71.84277777777778,-52.46944444444444,54.4875,71.84277777777778,71.84277777777778,145.3 +71.89222222222222,-52.50555555555555,54.525,71.89222222222222,71.89222222222222,145.4 +71.94166666666666,-52.541666666666664,54.5625,71.94166666666666,71.94166666666666,145.5 +71.99111111111111,-52.577777777777776,54.6,71.99111111111111,71.99111111111111,145.6 +72.04055555555556,-52.61388888888889,54.637499999999996,72.04055555555556,72.04055555555556,145.70000000000002 +72.09,-52.65,54.675,72.09,72.09,145.8 +72.13944444444445,-52.6861111111111,54.7125,72.13944444444445,72.13944444444445,145.9 +72.18888888888888,-52.722222222222214,54.75,72.18888888888888,72.18888888888888,146.0 +72.23833333333333,-52.758333333333326,54.7875,72.23833333333333,72.23833333333333,146.1 +72.28777777777778,-52.79444444444444,54.824999999999996,72.28777777777778,72.28777777777778,146.20000000000002 +72.33722222222222,-52.83055555555555,54.8625,72.33722222222222,72.33722222222222,146.3 +72.38666666666667,-52.86666666666666,54.9,72.38666666666667,72.38666666666667,146.4 +72.4361111111111,-52.90277777777777,54.9375,72.4361111111111,72.4361111111111,146.5 +72.48555555555555,-52.93888888888888,54.975,72.48555555555555,72.48555555555555,146.6 +72.535,-52.974999999999994,55.012499999999996,72.535,72.535,146.70000000000002 +72.58444444444444,-53.011111111111106,55.05,72.58444444444444,72.58444444444444,146.8 +72.63388888888889,-53.04722222222222,55.0875,72.63388888888889,72.63388888888889,146.9 +72.68333333333334,-53.08333333333333,55.125,72.68333333333334,72.68333333333334,147.0 +72.73277777777777,-53.11944444444444,55.1625,72.73277777777777,72.73277777777777,147.1 +72.78222222222222,-53.15555555555555,55.199999999999996,72.78222222222222,72.78222222222222,147.20000000000002 +72.83166666666666,-53.19166666666666,55.2375,72.83166666666666,72.83166666666666,147.3 +72.88111111111111,-53.227777777777774,55.275,72.88111111111111,72.88111111111111,147.4 +72.93055555555556,-53.263888888888886,55.3125,72.93055555555556,72.93055555555556,147.5 +72.98,-53.3,55.35,72.98,72.98,147.6 +73.02944444444444,-53.33611111111111,55.387499999999996,73.02944444444444,73.02944444444444,147.70000000000002 +73.07888888888888,-53.37222222222222,55.425,73.07888888888888,73.07888888888888,147.8 +73.12833333333333,-53.40833333333333,55.4625,73.12833333333333,73.12833333333333,147.9 +73.17777777777778,-53.44444444444444,55.5,73.17777777777778,73.17777777777778,148.0 +73.22722222222222,-53.48055555555555,55.5375,73.22722222222222,73.22722222222222,148.1 +73.27666666666667,-53.51666666666666,55.574999999999996,73.27666666666667,73.27666666666667,148.20000000000002 +73.3261111111111,-53.55277777777777,55.6125,73.3261111111111,73.3261111111111,148.3 +73.37555555555555,-53.58888888888888,55.65,73.37555555555555,73.37555555555555,148.4 +73.425,-53.62499999999999,55.6875,73.425,73.425,148.5 +73.47444444444444,-53.661111111111104,55.725,73.47444444444444,73.47444444444444,148.6 +73.52388888888889,-53.697222222222216,55.762499999999996,73.52388888888889,73.52388888888889,148.70000000000002 +73.57333333333334,-53.73333333333333,55.8,73.57333333333334,73.57333333333334,148.8 +73.62277777777777,-53.76944444444444,55.8375,73.62277777777777,73.62277777777777,148.9 +73.67222222222222,-53.80555555555555,55.875,73.67222222222222,73.67222222222222,149.0 +73.72166666666666,-53.84166666666666,55.9125,73.72166666666666,73.72166666666666,149.1 +73.77111111111111,-53.87777777777777,55.949999999999996,73.77111111111111,73.77111111111111,149.20000000000002 +73.82055555555556,-53.913888888888884,55.9875,73.82055555555556,73.82055555555556,149.3 +73.87,-53.949999999999996,56.025,73.87,73.87,149.4 +73.91944444444444,-53.98611111111111,56.0625,73.91944444444444,73.91944444444444,149.5 +73.96888888888888,-54.02222222222222,56.1,73.96888888888888,73.96888888888888,149.6 +74.01833333333333,-54.05833333333333,56.137499999999996,74.01833333333333,74.01833333333333,149.70000000000002 +74.06777777777778,-54.09444444444444,56.175,74.06777777777778,74.06777777777778,149.8 +74.11722222222222,-54.13055555555555,56.2125,74.11722222222222,74.11722222222222,149.9 +74.16666666666667,-54.166666666666664,56.25,74.16666666666667,74.16666666666667,150.0 +74.2161111111111,-54.202777777777776,56.2875,74.2161111111111,74.2161111111111,150.1 +74.26555555555555,-54.23888888888889,56.324999999999996,74.26555555555555,74.26555555555555,150.20000000000002 +74.315,-54.27499999999999,56.3625,74.315,74.315,150.3 +74.36444444444444,-54.3111111111111,56.4,74.36444444444444,74.36444444444444,150.4 +74.41388888888889,-54.347222222222214,56.4375,74.41388888888889,74.41388888888889,150.5 +74.46333333333334,-54.383333333333326,56.475,74.46333333333334,74.46333333333334,150.6 +74.51277777777777,-54.41944444444444,56.512499999999996,74.51277777777777,74.51277777777777,150.70000000000002 +74.56222222222222,-54.45555555555555,56.55,74.56222222222222,74.56222222222222,150.8 +74.61166666666666,-54.49166666666666,56.5875,74.61166666666666,74.61166666666666,150.9 +74.66111111111111,-54.52777777777777,56.625,74.66111111111111,74.66111111111111,151.0 +74.71055555555556,-54.56388888888888,56.6625,74.71055555555556,74.71055555555556,151.1 +74.76,-54.599999999999994,56.699999999999996,74.76,74.76,151.20000000000002 +74.80944444444444,-54.636111111111106,56.7375,74.80944444444444,74.80944444444444,151.3 +74.85888888888888,-54.67222222222222,56.775,74.85888888888888,74.85888888888888,151.4 +74.90833333333333,-54.70833333333333,56.8125,74.90833333333333,74.90833333333333,151.5 +74.95777777777778,-54.74444444444444,56.85,74.95777777777778,74.95777777777778,151.6 +75.00722222222223,-54.78055555555555,56.887499999999996,75.00722222222223,75.00722222222223,151.70000000000002 +75.05666666666667,-54.81666666666666,56.925,75.05666666666667,75.05666666666667,151.8 +75.1061111111111,-54.852777777777774,56.9625,75.1061111111111,75.1061111111111,151.9 +75.15555555555555,-54.888888888888886,57.0,75.15555555555555,75.15555555555555,152.0 +75.205,-54.925,57.0375,75.205,75.205,152.1 +75.25444444444445,-54.96111111111111,57.074999999999996,75.25444444444445,75.25444444444445,152.20000000000002 +75.30388888888889,-54.99722222222222,57.1125,75.30388888888889,75.30388888888889,152.3 +75.35333333333334,-55.03333333333333,57.15,75.35333333333334,75.35333333333334,152.4 +75.40277777777777,-55.069444444444436,57.1875,75.40277777777777,75.40277777777777,152.5 +75.45222222222222,-55.10555555555555,57.225,75.45222222222222,75.45222222222222,152.6 +75.50166666666667,-55.14166666666666,57.262499999999996,75.50166666666667,75.50166666666667,152.70000000000002 +75.55111111111111,-55.17777777777777,57.3,75.55111111111111,75.55111111111111,152.8 +75.60055555555556,-55.21388888888888,57.3375,75.60055555555556,75.60055555555556,152.9 +75.65,-55.24999999999999,57.375,75.65,75.65,153.0 +75.69944444444444,-55.286111111111104,57.4125,75.69944444444444,75.69944444444444,153.1 +75.74888888888889,-55.322222222222216,57.449999999999996,75.74888888888889,75.74888888888889,153.20000000000002 +75.79833333333333,-55.35833333333333,57.4875,75.79833333333333,75.79833333333333,153.3 +75.84777777777778,-55.39444444444444,57.525,75.84777777777778,75.84777777777778,153.4 +75.89722222222223,-55.43055555555555,57.5625,75.89722222222223,75.89722222222223,153.5 +75.94666666666666,-55.46666666666666,57.599999999999994,75.94666666666666,75.94666666666666,153.60000000000002 +75.9961111111111,-55.50277777777777,57.637499999999996,75.9961111111111,75.9961111111111,153.70000000000002 +76.04555555555555,-55.538888888888884,57.675,76.04555555555555,76.04555555555555,153.8 +76.095,-55.574999999999996,57.7125,76.095,76.095,153.9 +76.14444444444445,-55.61111111111111,57.75,76.14444444444445,76.14444444444445,154.0 +76.19388888888889,-55.64722222222222,57.787499999999994,76.19388888888889,76.19388888888889,154.10000000000002 +76.24333333333333,-55.68333333333333,57.824999999999996,76.24333333333333,76.24333333333333,154.20000000000002 +76.29277777777777,-55.71944444444444,57.8625,76.29277777777777,76.29277777777777,154.3 +76.34222222222222,-55.75555555555555,57.9,76.34222222222222,76.34222222222222,154.4 +76.39166666666667,-55.791666666666664,57.9375,76.39166666666667,76.39166666666667,154.5 +76.44111111111111,-55.827777777777776,57.974999999999994,76.44111111111111,76.44111111111111,154.60000000000002 +76.49055555555556,-55.86388888888889,58.012499999999996,76.49055555555556,76.49055555555556,154.70000000000002 +76.53999999999999,-55.89999999999999,58.05,76.53999999999999,76.53999999999999,154.8 +76.58944444444444,-55.9361111111111,58.0875,76.58944444444444,76.58944444444444,154.9 +76.63888888888889,-55.972222222222214,58.125,76.63888888888889,76.63888888888889,155.0 +76.68833333333333,-56.008333333333326,58.162499999999994,76.68833333333333,76.68833333333333,155.10000000000002 +76.73777777777778,-56.04444444444444,58.199999999999996,76.73777777777778,76.73777777777778,155.20000000000002 +76.78722222222223,-56.08055555555555,58.2375,76.78722222222223,76.78722222222223,155.3 +76.83666666666666,-56.11666666666666,58.275,76.83666666666666,76.83666666666666,155.4 +76.8861111111111,-56.15277777777777,58.3125,76.8861111111111,76.8861111111111,155.5 +76.93555555555555,-56.18888888888888,58.349999999999994,76.93555555555555,76.93555555555555,155.60000000000002 +76.985,-56.224999999999994,58.387499999999996,76.985,76.985,155.70000000000002 +77.03444444444445,-56.261111111111106,58.425,77.03444444444445,77.03444444444445,155.8 +77.0838888888889,-56.29722222222222,58.4625,77.0838888888889,77.0838888888889,155.9 +77.13333333333333,-56.33333333333333,58.5,77.13333333333333,77.13333333333333,156.0 +77.18277777777777,-56.36944444444444,58.537499999999994,77.18277777777777,77.18277777777777,156.10000000000002 +77.23222222222222,-56.40555555555555,58.574999999999996,77.23222222222222,77.23222222222222,156.20000000000002 +77.28166666666667,-56.44166666666666,58.6125,77.28166666666667,77.28166666666667,156.3 +77.33111111111111,-56.477777777777774,58.65,77.33111111111111,77.33111111111111,156.4 +77.38055555555556,-56.513888888888886,58.6875,77.38055555555556,77.38055555555556,156.5 +77.42999999999999,-56.55,58.724999999999994,77.42999999999999,77.42999999999999,156.60000000000002 +77.47944444444444,-56.58611111111111,58.762499999999996,77.47944444444444,77.47944444444444,156.70000000000002 +77.52888888888889,-56.62222222222222,58.8,77.52888888888889,77.52888888888889,156.8 +77.57833333333333,-56.65833333333333,58.8375,77.57833333333333,77.57833333333333,156.9 +77.62777777777778,-56.694444444444436,58.875,77.62777777777778,77.62777777777778,157.0 +77.67722222222223,-56.73055555555555,58.912499999999994,77.67722222222223,77.67722222222223,157.10000000000002 +77.72666666666666,-56.76666666666666,58.949999999999996,77.72666666666666,77.72666666666666,157.20000000000002 +77.7761111111111,-56.80277777777777,58.9875,77.7761111111111,77.7761111111111,157.3 +77.82555555555555,-56.83888888888888,59.025,77.82555555555555,77.82555555555555,157.4 +77.875,-56.87499999999999,59.0625,77.875,77.875,157.5 +77.92444444444445,-56.911111111111104,59.099999999999994,77.92444444444445,77.92444444444445,157.60000000000002 +77.9738888888889,-56.947222222222216,59.137499999999996,77.9738888888889,77.9738888888889,157.70000000000002 +78.02333333333333,-56.98333333333333,59.175,78.02333333333333,78.02333333333333,157.8 +78.07277777777777,-57.01944444444444,59.2125,78.07277777777777,78.07277777777777,157.9 +78.12222222222222,-57.05555555555555,59.25,78.12222222222222,78.12222222222222,158.0 +78.17166666666667,-57.09166666666666,59.287499999999994,78.17166666666667,78.17166666666667,158.10000000000002 +78.22111111111111,-57.12777777777777,59.324999999999996,78.22111111111111,78.22111111111111,158.20000000000002 +78.27055555555556,-57.163888888888884,59.3625,78.27055555555556,78.27055555555556,158.3 +78.32,-57.199999999999996,59.4,78.32,78.32,158.4 +78.36944444444444,-57.23611111111111,59.4375,78.36944444444444,78.36944444444444,158.5 +78.41888888888889,-57.27222222222222,59.474999999999994,78.41888888888889,78.41888888888889,158.60000000000002 +78.46833333333333,-57.30833333333333,59.512499999999996,78.46833333333333,78.46833333333333,158.70000000000002 +78.51777777777778,-57.34444444444444,59.55,78.51777777777778,78.51777777777778,158.8 +78.56722222222223,-57.38055555555555,59.5875,78.56722222222223,78.56722222222223,158.9 +78.61666666666666,-57.416666666666664,59.625,78.61666666666666,78.61666666666666,159.0 +78.6661111111111,-57.452777777777776,59.662499999999994,78.6661111111111,78.6661111111111,159.10000000000002 +78.71555555555555,-57.48888888888888,59.699999999999996,78.71555555555555,78.71555555555555,159.20000000000002 +78.765,-57.52499999999999,59.7375,78.765,78.765,159.3 +78.81444444444445,-57.5611111111111,59.775,78.81444444444445,78.81444444444445,159.4 +78.8638888888889,-57.597222222222214,59.8125,78.8638888888889,78.8638888888889,159.5 +78.91333333333333,-57.633333333333326,59.849999999999994,78.91333333333333,78.91333333333333,159.60000000000002 +78.96277777777777,-57.66944444444444,59.887499999999996,78.96277777777777,78.96277777777777,159.70000000000002 +79.01222222222222,-57.70555555555555,59.925,79.01222222222222,79.01222222222222,159.8 +79.06166666666667,-57.74166666666666,59.9625,79.06166666666667,79.06166666666667,159.9 +79.11111111111111,-57.77777777777777,60.0,79.11111111111111,79.11111111111111,160.0 +79.16055555555556,-57.81388888888888,60.037499999999994,79.16055555555556,79.16055555555556,160.10000000000002 +79.21,-57.849999999999994,60.074999999999996,79.21,79.21,160.20000000000002 +79.25944444444444,-57.886111111111106,60.1125,79.25944444444444,79.25944444444444,160.3 +79.30888888888889,-57.92222222222222,60.15,79.30888888888889,79.30888888888889,160.4 +79.35833333333333,-57.95833333333333,60.1875,79.35833333333333,79.35833333333333,160.5 +79.40777777777778,-57.99444444444444,60.224999999999994,79.40777777777778,79.40777777777778,160.60000000000002 +79.45722222222223,-58.03055555555555,60.262499999999996,79.45722222222223,79.45722222222223,160.70000000000002 +79.50666666666666,-58.06666666666666,60.3,79.50666666666666,79.50666666666666,160.8 +79.55611111111111,-58.102777777777774,60.3375,79.55611111111111,79.55611111111111,160.9 +79.60555555555555,-58.138888888888886,60.375,79.60555555555555,79.60555555555555,161.0 +79.655,-58.175,60.412499999999994,79.655,79.655,161.10000000000002 +79.70444444444445,-58.21111111111111,60.449999999999996,79.70444444444445,79.70444444444445,161.20000000000002 +79.75388888888888,-58.24722222222222,60.4875,79.75388888888888,79.75388888888888,161.3 +79.80333333333333,-58.283333333333324,60.525,79.80333333333333,79.80333333333333,161.4 +79.85277777777777,-58.319444444444436,60.5625,79.85277777777777,79.85277777777777,161.5 +79.90222222222222,-58.35555555555555,60.599999999999994,79.90222222222222,79.90222222222222,161.60000000000002 +79.95166666666667,-58.39166666666666,60.637499999999996,79.95166666666667,79.95166666666667,161.70000000000002 +80.00111111111111,-58.42777777777777,60.675,80.00111111111111,80.00111111111111,161.8 +80.05055555555555,-58.46388888888888,60.7125,80.05055555555555,80.05055555555555,161.9 +80.1,-58.49999999999999,60.75,80.1,80.1,162.0 +80.14944444444444,-58.536111111111104,60.787499999999994,80.14944444444444,80.14944444444444,162.10000000000002 +80.19888888888889,-58.572222222222216,60.824999999999996,80.19888888888889,80.19888888888889,162.20000000000002 +80.24833333333333,-58.60833333333333,60.8625,80.24833333333333,80.24833333333333,162.3 +80.29777777777778,-58.64444444444444,60.9,80.29777777777778,80.29777777777778,162.4 +80.34722222222221,-58.68055555555555,60.9375,80.34722222222221,80.34722222222221,162.5 +80.39666666666666,-58.71666666666666,60.974999999999994,80.39666666666666,80.39666666666666,162.60000000000002 +80.44611111111111,-58.75277777777777,61.012499999999996,80.44611111111111,80.44611111111111,162.70000000000002 +80.49555555555555,-58.788888888888884,61.05,80.49555555555555,80.49555555555555,162.8 +80.545,-58.824999999999996,61.0875,80.545,80.545,162.9 +80.59444444444445,-58.86111111111111,61.125,80.59444444444445,80.59444444444445,163.0 +80.64388888888888,-58.89722222222222,61.162499999999994,80.64388888888888,80.64388888888888,163.10000000000002 +80.69333333333333,-58.93333333333333,61.199999999999996,80.69333333333333,80.69333333333333,163.20000000000002 +80.74277777777777,-58.96944444444444,61.2375,80.74277777777777,80.74277777777777,163.3 +80.79222222222222,-59.00555555555555,61.275,80.79222222222222,80.79222222222222,163.4 +80.84166666666667,-59.041666666666664,61.3125,80.84166666666667,80.84166666666667,163.5 +80.89111111111112,-59.077777777777776,61.349999999999994,80.89111111111112,80.89111111111112,163.60000000000002 +80.94055555555555,-59.11388888888888,61.387499999999996,80.94055555555555,80.94055555555555,163.70000000000002 +80.99,-59.14999999999999,61.425,80.99,80.99,163.8 +81.03944444444444,-59.1861111111111,61.4625,81.03944444444444,81.03944444444444,163.9 +81.08888888888889,-59.222222222222214,61.5,81.08888888888889,81.08888888888889,164.0 +81.13833333333334,-59.258333333333326,61.537499999999994,81.13833333333334,81.13833333333334,164.10000000000002 +81.18777777777778,-59.29444444444444,61.574999999999996,81.18777777777778,81.18777777777778,164.20000000000002 +81.23722222222221,-59.33055555555555,61.6125,81.23722222222221,81.23722222222221,164.3 +81.28666666666666,-59.36666666666666,61.65,81.28666666666666,81.28666666666666,164.4 +81.33611111111111,-59.40277777777777,61.6875,81.33611111111111,81.33611111111111,164.5 +81.38555555555556,-59.43888888888888,61.724999999999994,81.38555555555556,81.38555555555556,164.60000000000002 +81.435,-59.474999999999994,61.762499999999996,81.435,81.435,164.70000000000002 +81.48444444444445,-59.511111111111106,61.8,81.48444444444445,81.48444444444445,164.8 +81.53388888888888,-59.54722222222222,61.8375,81.53388888888888,81.53388888888888,164.9 +81.58333333333333,-59.58333333333333,61.875,81.58333333333333,81.58333333333333,165.0 +81.63277777777778,-59.61944444444444,61.912499999999994,81.63277777777778,81.63277777777778,165.10000000000002 +81.68222222222222,-59.65555555555555,61.949999999999996,81.68222222222222,81.68222222222222,165.20000000000002 +81.73166666666667,-59.69166666666666,61.9875,81.73166666666667,81.73166666666667,165.3 +81.78111111111112,-59.727777777777774,62.025,81.78111111111112,81.78111111111112,165.4 +81.83055555555555,-59.763888888888886,62.0625,81.83055555555555,81.83055555555555,165.5 +81.88,-59.8,62.099999999999994,81.88,81.88,165.60000000000002 +81.92944444444444,-59.83611111111111,62.137499999999996,81.92944444444444,81.92944444444444,165.70000000000002 +81.97888888888889,-59.87222222222222,62.175,81.97888888888889,81.97888888888889,165.8 +82.02833333333334,-59.908333333333324,62.2125,82.02833333333334,82.02833333333334,165.9 +82.07777777777778,-59.944444444444436,62.25,82.07777777777778,82.07777777777778,166.0 +82.12722222222222,-59.98055555555555,62.287499999999994,82.12722222222222,82.12722222222222,166.10000000000002 +82.17666666666666,-60.01666666666666,62.324999999999996,82.17666666666666,82.17666666666666,166.20000000000002 +82.22611111111111,-60.05277777777777,62.3625,82.22611111111111,82.22611111111111,166.3 +82.27555555555556,-60.08888888888888,62.4,82.27555555555556,82.27555555555556,166.4 +82.325,-60.12499999999999,62.4375,82.325,82.325,166.5 +82.37444444444445,-60.161111111111104,62.474999999999994,82.37444444444445,82.37444444444445,166.60000000000002 +82.42388888888888,-60.197222222222216,62.512499999999996,82.42388888888888,82.42388888888888,166.70000000000002 +82.47333333333333,-60.23333333333333,62.55,82.47333333333333,82.47333333333333,166.8 +82.52277777777778,-60.26944444444444,62.5875,82.52277777777778,82.52277777777778,166.9 +82.57222222222222,-60.30555555555555,62.625,82.57222222222222,82.57222222222222,167.0 +82.62166666666667,-60.34166666666666,62.662499999999994,82.62166666666667,82.62166666666667,167.10000000000002 +82.67111111111112,-60.37777777777777,62.699999999999996,82.67111111111112,82.67111111111112,167.20000000000002 +82.72055555555555,-60.413888888888884,62.7375,82.72055555555555,82.72055555555555,167.3 +82.77,-60.449999999999996,62.775,82.77,82.77,167.4 +82.81944444444444,-60.48611111111111,62.8125,82.81944444444444,82.81944444444444,167.5 +82.86888888888889,-60.52222222222222,62.849999999999994,82.86888888888889,82.86888888888889,167.60000000000002 +82.91833333333334,-60.55833333333333,62.887499999999996,82.91833333333334,82.91833333333334,167.70000000000002 +82.96777777777778,-60.59444444444444,62.925,82.96777777777778,82.96777777777778,167.8 +83.01722222222222,-60.63055555555555,62.9625,83.01722222222222,83.01722222222222,167.9 +83.06666666666666,-60.666666666666664,63.0,83.06666666666666,83.06666666666666,168.0 +83.11611111111111,-60.70277777777777,63.037499999999994,83.11611111111111,83.11611111111111,168.10000000000002 +83.16555555555556,-60.73888888888888,63.074999999999996,83.16555555555556,83.16555555555556,168.20000000000002 +83.215,-60.77499999999999,63.1125,83.215,83.215,168.3 +83.26444444444444,-60.8111111111111,63.15,83.26444444444444,83.26444444444444,168.4 +83.31388888888888,-60.847222222222214,63.1875,83.31388888888888,83.31388888888888,168.5 +83.36333333333333,-60.883333333333326,63.224999999999994,83.36333333333333,83.36333333333333,168.60000000000002 +83.41277777777778,-60.91944444444444,63.262499999999996,83.41277777777778,83.41277777777778,168.70000000000002 +83.46222222222222,-60.95555555555555,63.3,83.46222222222222,83.46222222222222,168.8 +83.51166666666667,-60.99166666666666,63.3375,83.51166666666667,83.51166666666667,168.9 +83.5611111111111,-61.02777777777777,63.375,83.5611111111111,83.5611111111111,169.0 +83.61055555555555,-61.06388888888888,63.412499999999994,83.61055555555555,83.61055555555555,169.10000000000002 +83.66,-61.099999999999994,63.449999999999996,83.66,83.66,169.20000000000002 +83.70944444444444,-61.136111111111106,63.4875,83.70944444444444,83.70944444444444,169.3 +83.75888888888889,-61.17222222222222,63.525,83.75888888888889,83.75888888888889,169.4 +83.80833333333334,-61.20833333333333,63.5625,83.80833333333334,83.80833333333334,169.5 +83.85777777777777,-61.24444444444444,63.599999999999994,83.85777777777777,83.85777777777777,169.60000000000002 +83.90722222222222,-61.28055555555555,63.637499999999996,83.90722222222222,83.90722222222222,169.70000000000002 +83.95666666666666,-61.31666666666666,63.675,83.95666666666666,83.95666666666666,169.8 +84.00611111111111,-61.352777777777774,63.7125,84.00611111111111,84.00611111111111,169.9 +84.05555555555556,-61.388888888888886,63.75,84.05555555555556,84.05555555555556,170.0 +84.105,-61.425,63.787499999999994,84.105,84.105,170.10000000000002 +84.15444444444444,-61.46111111111111,63.824999999999996,84.15444444444444,84.15444444444444,170.20000000000002 +84.20388888888888,-61.49722222222221,63.8625,84.20388888888888,84.20388888888888,170.3 +84.25333333333333,-61.533333333333324,63.9,84.25333333333333,84.25333333333333,170.4 +84.30277777777778,-61.569444444444436,63.9375,84.30277777777778,84.30277777777778,170.5 +84.35222222222222,-61.60555555555555,63.974999999999994,84.35222222222222,84.35222222222222,170.60000000000002 +84.40166666666667,-61.64166666666666,64.0125,84.40166666666667,84.40166666666667,170.70000000000002 +84.4511111111111,-61.67777777777777,64.05,84.4511111111111,84.4511111111111,170.8 +84.50055555555555,-61.71388888888888,64.08749999999999,84.50055555555555,84.50055555555555,170.9 +84.55,-61.74999999999999,64.125,84.55,84.55,171.0 +84.59944444444444,-61.786111111111104,64.1625,84.59944444444444,84.59944444444444,171.10000000000002 +84.64888888888889,-61.822222222222216,64.2,84.64888888888889,84.64888888888889,171.20000000000002 +84.69833333333334,-61.85833333333333,64.2375,84.69833333333334,84.69833333333334,171.3 +84.74777777777777,-61.89444444444444,64.27499999999999,84.74777777777777,84.74777777777777,171.4 +84.79722222222222,-61.93055555555555,64.3125,84.79722222222222,84.79722222222222,171.5 +84.84666666666666,-61.96666666666666,64.35,84.84666666666666,84.84666666666666,171.60000000000002 +84.89611111111111,-62.00277777777777,64.3875,84.89611111111111,84.89611111111111,171.70000000000002 +84.94555555555556,-62.038888888888884,64.425,84.94555555555556,84.94555555555556,171.8 +84.995,-62.074999999999996,64.46249999999999,84.995,84.995,171.9 +85.04444444444444,-62.11111111111111,64.5,85.04444444444444,85.04444444444444,172.0 +85.09388888888888,-62.14722222222222,64.5375,85.09388888888888,85.09388888888888,172.10000000000002 +85.14333333333333,-62.18333333333333,64.575,85.14333333333333,85.14333333333333,172.20000000000002 +85.19277777777778,-62.21944444444444,64.6125,85.19277777777778,85.19277777777778,172.3 +85.24222222222222,-62.25555555555555,64.64999999999999,85.24222222222222,85.24222222222222,172.4 +85.29166666666667,-62.291666666666664,64.6875,85.29166666666667,85.29166666666667,172.5 +85.3411111111111,-62.32777777777777,64.725,85.3411111111111,85.3411111111111,172.60000000000002 +85.39055555555555,-62.36388888888888,64.7625,85.39055555555555,85.39055555555555,172.70000000000002 +85.44,-62.39999999999999,64.8,85.44,85.44,172.8 +85.48944444444444,-62.4361111111111,64.83749999999999,85.48944444444444,85.48944444444444,172.9 +85.53888888888889,-62.472222222222214,64.875,85.53888888888889,85.53888888888889,173.0 +85.58833333333334,-62.508333333333326,64.9125,85.58833333333334,85.58833333333334,173.10000000000002 +85.63777777777777,-62.54444444444444,64.95,85.63777777777777,85.63777777777777,173.20000000000002 +85.68722222222222,-62.58055555555555,64.9875,85.68722222222222,85.68722222222222,173.3 +85.73666666666666,-62.61666666666666,65.02499999999999,85.73666666666666,85.73666666666666,173.4 +85.78611111111111,-62.65277777777777,65.0625,85.78611111111111,85.78611111111111,173.5 +85.83555555555556,-62.68888888888888,65.1,85.83555555555556,85.83555555555556,173.60000000000002 +85.885,-62.724999999999994,65.1375,85.885,85.885,173.70000000000002 +85.93444444444444,-62.761111111111106,65.175,85.93444444444444,85.93444444444444,173.8 +85.98388888888888,-62.79722222222222,65.21249999999999,85.98388888888888,85.98388888888888,173.9 +86.03333333333333,-62.83333333333333,65.25,86.03333333333333,86.03333333333333,174.0 +86.08277777777778,-62.86944444444444,65.2875,86.08277777777778,86.08277777777778,174.10000000000002 +86.13222222222223,-62.90555555555555,65.325,86.13222222222223,86.13222222222223,174.20000000000002 +86.18166666666667,-62.94166666666666,65.3625,86.18166666666667,86.18166666666667,174.3 +86.2311111111111,-62.977777777777774,65.39999999999999,86.2311111111111,86.2311111111111,174.4 +86.28055555555555,-63.013888888888886,65.4375,86.28055555555555,86.28055555555555,174.5 +86.33,-63.05,65.475,86.33,86.33,174.60000000000002 +86.37944444444445,-63.08611111111111,65.5125,86.37944444444445,86.37944444444445,174.70000000000002 +86.42888888888889,-63.12222222222221,65.55,86.42888888888889,86.42888888888889,174.8 +86.47833333333334,-63.158333333333324,65.58749999999999,86.47833333333334,86.47833333333334,174.9 +86.52777777777777,-63.194444444444436,65.625,86.52777777777777,86.52777777777777,175.0 +86.57722222222222,-63.23055555555555,65.6625,86.57722222222222,86.57722222222222,175.10000000000002 +86.62666666666667,-63.26666666666666,65.7,86.62666666666667,86.62666666666667,175.20000000000002 +86.67611111111111,-63.30277777777777,65.7375,86.67611111111111,86.67611111111111,175.3 +86.72555555555556,-63.33888888888888,65.77499999999999,86.72555555555556,86.72555555555556,175.4 +86.775,-63.37499999999999,65.8125,86.775,86.775,175.5 +86.82444444444444,-63.411111111111104,65.85,86.82444444444444,86.82444444444444,175.60000000000002 +86.87388888888889,-63.447222222222216,65.8875,86.87388888888889,86.87388888888889,175.70000000000002 +86.92333333333333,-63.48333333333333,65.925,86.92333333333333,86.92333333333333,175.8 +86.97277777777778,-63.51944444444444,65.96249999999999,86.97277777777778,86.97277777777778,175.9 +87.02222222222223,-63.55555555555555,66.0,87.02222222222223,87.02222222222223,176.0 +87.07166666666666,-63.59166666666666,66.0375,87.07166666666666,87.07166666666666,176.10000000000002 +87.1211111111111,-63.62777777777777,66.075,87.1211111111111,87.1211111111111,176.20000000000002 +87.17055555555555,-63.663888888888884,66.1125,87.17055555555555,87.17055555555555,176.3 +87.22,-63.699999999999996,66.14999999999999,87.22,87.22,176.4 +87.26944444444445,-63.73611111111111,66.1875,87.26944444444445,87.26944444444445,176.5 +87.31888888888889,-63.77222222222222,66.225,87.31888888888889,87.31888888888889,176.60000000000002 +87.36833333333333,-63.80833333333333,66.2625,87.36833333333333,87.36833333333333,176.70000000000002 +87.41777777777777,-63.84444444444444,66.3,87.41777777777777,87.41777777777777,176.8 +87.46722222222222,-63.88055555555555,66.33749999999999,87.46722222222222,87.46722222222222,176.9 +87.51666666666667,-63.91666666666666,66.375,87.51666666666667,87.51666666666667,177.0 +87.56611111111111,-63.95277777777777,66.4125,87.56611111111111,87.56611111111111,177.10000000000002 +87.61555555555556,-63.98888888888888,66.45,87.61555555555556,87.61555555555556,177.20000000000002 +87.66499999999999,-64.02499999999999,66.4875,87.66499999999999,87.66499999999999,177.3 +87.71444444444444,-64.0611111111111,66.52499999999999,87.71444444444444,87.71444444444444,177.4 +87.76388888888889,-64.09722222222221,66.5625,87.76388888888889,87.76388888888889,177.5 +87.81333333333333,-64.13333333333333,66.6,87.81333333333333,87.81333333333333,177.60000000000002 +87.86277777777778,-64.16944444444444,66.6375,87.86277777777778,87.86277777777778,177.70000000000002 +87.91222222222223,-64.20555555555555,66.675,87.91222222222223,87.91222222222223,177.8 +87.96166666666666,-64.24166666666666,66.71249999999999,87.96166666666666,87.96166666666666,177.9 +88.0111111111111,-64.27777777777777,66.75,88.0111111111111,88.0111111111111,178.0 +88.06055555555555,-64.31388888888888,66.7875,88.06055555555555,88.06055555555555,178.10000000000002 +88.11,-64.35,66.825,88.11,88.11,178.20000000000002 +88.15944444444445,-64.3861111111111,66.8625,88.15944444444445,88.15944444444445,178.3 +88.2088888888889,-64.42222222222222,66.89999999999999,88.2088888888889,88.2088888888889,178.4 +88.25833333333333,-64.45833333333333,66.9375,88.25833333333333,88.25833333333333,178.5 +88.30777777777777,-64.49444444444444,66.975,88.30777777777777,88.30777777777777,178.60000000000002 +88.35722222222222,-64.53055555555555,67.0125,88.35722222222222,88.35722222222222,178.70000000000002 +88.40666666666667,-64.56666666666666,67.05,88.40666666666667,88.40666666666667,178.8 +88.45611111111111,-64.60277777777777,67.08749999999999,88.45611111111111,88.45611111111111,178.9 +88.50555555555556,-64.63888888888889,67.125,88.50555555555556,88.50555555555556,179.0 +88.55499999999999,-64.675,67.1625,88.55499999999999,88.55499999999999,179.10000000000002 +88.60444444444444,-64.71111111111111,67.2,88.60444444444444,88.60444444444444,179.20000000000002 +88.65388888888889,-64.74722222222222,67.2375,88.65388888888889,88.65388888888889,179.3 +88.70333333333333,-64.78333333333333,67.27499999999999,88.70333333333333,88.70333333333333,179.4 +88.75277777777778,-64.81944444444444,67.3125,88.75277777777778,88.75277777777778,179.5 +88.80222222222223,-64.85555555555555,67.35,88.80222222222223,88.80222222222223,179.60000000000002 +88.85166666666666,-64.89166666666667,67.3875,88.85166666666666,88.85166666666666,179.70000000000002 +88.9011111111111,-64.92777777777778,67.425,88.9011111111111,88.9011111111111,179.8 +88.95055555555555,-64.96388888888889,67.46249999999999,88.95055555555555,88.95055555555555,179.9 +89.0,-65.0,67.5,89.0,89.0,180.0 +89.04944444444445,-65.03611111111111,67.5375,89.04944444444445,89.04944444444445,180.10000000000002 +89.0988888888889,-65.07222222222222,67.575,89.0988888888889,89.0988888888889,180.20000000000002 +89.14833333333333,-65.10833333333333,67.6125,89.14833333333333,89.14833333333333,180.3 +89.19777777777777,-65.14444444444443,67.64999999999999,89.19777777777777,89.19777777777777,180.4 +89.24722222222222,-65.18055555555554,67.6875,89.24722222222222,89.24722222222222,180.5 +89.29666666666667,-65.21666666666665,67.725,89.29666666666667,89.29666666666667,180.60000000000002 +89.34611111111111,-65.25277777777777,67.7625,89.34611111111111,89.34611111111111,180.70000000000002 +89.39555555555556,-65.28888888888888,67.8,89.39555555555556,89.39555555555556,180.8 +89.445,-65.32499999999999,67.83749999999999,89.445,89.445,180.9 +89.49444444444444,-65.3611111111111,67.875,89.49444444444444,89.49444444444444,181.0 +89.54388888888889,-65.39722222222221,67.9125,89.54388888888889,89.54388888888889,181.10000000000002 +89.59333333333333,-65.43333333333332,67.95,89.59333333333333,89.59333333333333,181.20000000000002 +89.64277777777778,-65.46944444444443,67.9875,89.64277777777778,89.64277777777778,181.3 +89.69222222222223,-65.50555555555555,68.02499999999999,89.69222222222223,89.69222222222223,181.4 +89.74166666666666,-65.54166666666666,68.0625,89.74166666666666,89.74166666666666,181.5 +89.7911111111111,-65.57777777777777,68.1,89.7911111111111,89.7911111111111,181.60000000000002 +89.84055555555555,-65.61388888888888,68.1375,89.84055555555555,89.84055555555555,181.70000000000002 +89.89,-65.64999999999999,68.175,89.89,89.89,181.8 +89.93944444444445,-65.6861111111111,68.21249999999999,89.93944444444445,89.93944444444445,181.9 +89.9888888888889,-65.72222222222221,68.25,89.9888888888889,89.9888888888889,182.0 +90.03833333333333,-65.75833333333333,68.2875,90.03833333333333,90.03833333333333,182.10000000000002 +90.08777777777777,-65.79444444444444,68.325,90.08777777777777,90.08777777777777,182.20000000000002 +90.13722222222222,-65.83055555555555,68.3625,90.13722222222222,90.13722222222222,182.3 +90.18666666666667,-65.86666666666666,68.39999999999999,90.18666666666667,90.18666666666667,182.4 +90.23611111111111,-65.90277777777777,68.4375,90.23611111111111,90.23611111111111,182.5 +90.28555555555556,-65.93888888888888,68.475,90.28555555555556,90.28555555555556,182.60000000000002 +90.335,-65.975,68.5125,90.335,90.335,182.70000000000002 +90.38444444444444,-66.0111111111111,68.55,90.38444444444444,90.38444444444444,182.8 +90.43388888888889,-66.04722222222222,68.58749999999999,90.43388888888889,90.43388888888889,182.9 +90.48333333333333,-66.08333333333333,68.625,90.48333333333333,90.48333333333333,183.0 +90.53277777777778,-66.11944444444444,68.6625,90.53277777777778,90.53277777777778,183.10000000000002 +90.58222222222221,-66.15555555555555,68.7,90.58222222222221,90.58222222222221,183.20000000000002 +90.63166666666666,-66.19166666666666,68.7375,90.63166666666666,90.63166666666666,183.3 +90.68111111111111,-66.22777777777777,68.77499999999999,90.68111111111111,90.68111111111111,183.4 +90.73055555555555,-66.26388888888889,68.8125,90.73055555555555,90.73055555555555,183.5 +90.78,-66.3,68.85,90.78,90.78,183.60000000000002 +90.82944444444445,-66.33611111111111,68.8875,90.82944444444445,90.82944444444445,183.70000000000002 +90.87888888888888,-66.37222222222222,68.925,90.87888888888888,90.87888888888888,183.8 +90.92833333333333,-66.40833333333333,68.96249999999999,90.92833333333333,90.92833333333333,183.9 +90.97777777777777,-66.44444444444444,69.0,90.97777777777777,90.97777777777777,184.0 +91.02722222222222,-66.48055555555555,69.0375,91.02722222222222,91.02722222222222,184.10000000000002 +91.07666666666667,-66.51666666666667,69.075,91.07666666666667,91.07666666666667,184.20000000000002 +91.12611111111111,-66.55277777777778,69.1125,91.12611111111111,91.12611111111111,184.3 +91.17555555555555,-66.58888888888889,69.14999999999999,91.17555555555555,91.17555555555555,184.4 +91.225,-66.625,69.1875,91.225,91.225,184.5 +91.27444444444444,-66.66111111111111,69.225,91.27444444444444,91.27444444444444,184.60000000000002 +91.32388888888889,-66.69722222222222,69.2625,91.32388888888889,91.32388888888889,184.70000000000002 +91.37333333333333,-66.73333333333332,69.3,91.37333333333333,91.37333333333333,184.8 +91.42277777777778,-66.76944444444443,69.33749999999999,91.42277777777778,91.42277777777778,184.9 +91.47222222222221,-66.80555555555554,69.375,91.47222222222221,91.47222222222221,185.0 +91.52166666666666,-66.84166666666665,69.4125,91.52166666666666,91.52166666666666,185.10000000000002 +91.57111111111111,-66.87777777777777,69.45,91.57111111111111,91.57111111111111,185.20000000000002 +91.62055555555555,-66.91388888888888,69.4875,91.62055555555555,91.62055555555555,185.3 +91.67,-66.94999999999999,69.52499999999999,91.67,91.67,185.4 +91.71944444444445,-66.9861111111111,69.5625,91.71944444444445,91.71944444444445,185.5 +91.76888888888888,-67.02222222222221,69.6,91.76888888888888,91.76888888888888,185.60000000000002 +91.81833333333333,-67.05833333333332,69.6375,91.81833333333333,91.81833333333333,185.70000000000002 +91.86777777777777,-67.09444444444443,69.675,91.86777777777777,91.86777777777777,185.8 +91.91722222222222,-67.13055555555555,69.71249999999999,91.91722222222222,91.91722222222222,185.9 +91.96666666666667,-67.16666666666666,69.75,91.96666666666667,91.96666666666667,186.0 +92.01611111111112,-67.20277777777777,69.7875,92.01611111111112,92.01611111111112,186.10000000000002 +92.06555555555555,-67.23888888888888,69.825,92.06555555555555,92.06555555555555,186.20000000000002 +92.115,-67.27499999999999,69.8625,92.115,92.115,186.3 +92.16444444444444,-67.3111111111111,69.89999999999999,92.16444444444444,92.16444444444444,186.4 +92.21388888888889,-67.34722222222221,69.9375,92.21388888888889,92.21388888888889,186.5 +92.26333333333334,-67.38333333333333,69.975,92.26333333333334,92.26333333333334,186.60000000000002 +92.31277777777778,-67.41944444444444,70.0125,92.31277777777778,92.31277777777778,186.70000000000002 +92.36222222222221,-67.45555555555555,70.05,92.36222222222221,92.36222222222221,186.8 +92.41166666666666,-67.49166666666666,70.08749999999999,92.41166666666666,92.41166666666666,186.9 +92.46111111111111,-67.52777777777777,70.125,92.46111111111111,92.46111111111111,187.0 +92.51055555555556,-67.56388888888888,70.1625,92.51055555555556,92.51055555555556,187.10000000000002 +92.56,-67.6,70.2,92.56,92.56,187.20000000000002 +92.60944444444445,-67.6361111111111,70.2375,92.60944444444445,92.60944444444445,187.3 +92.65888888888888,-67.67222222222222,70.27499999999999,92.65888888888888,92.65888888888888,187.4 +92.70833333333333,-67.70833333333333,70.3125,92.70833333333333,92.70833333333333,187.5 +92.75777777777778,-67.74444444444444,70.35,92.75777777777778,92.75777777777778,187.60000000000002 +92.80722222222222,-67.78055555555555,70.3875,92.80722222222222,92.80722222222222,187.70000000000002 +92.85666666666667,-67.81666666666666,70.425,92.85666666666667,92.85666666666667,187.8 +92.90611111111112,-67.85277777777777,70.46249999999999,92.90611111111112,92.90611111111112,187.9 +92.95555555555555,-67.88888888888889,70.5,92.95555555555555,92.95555555555555,188.0 +93.005,-67.925,70.5375,93.005,93.005,188.10000000000002 +93.05444444444444,-67.96111111111111,70.575,93.05444444444444,93.05444444444444,188.20000000000002 +93.10388888888889,-67.99722222222222,70.6125,93.10388888888889,93.10388888888889,188.3 +93.15333333333334,-68.03333333333333,70.64999999999999,93.15333333333334,93.15333333333334,188.4 +93.20277777777778,-68.06944444444444,70.6875,93.20277777777778,93.20277777777778,188.5 +93.25222222222222,-68.10555555555555,70.725,93.25222222222222,93.25222222222222,188.60000000000002 +93.30166666666666,-68.14166666666667,70.7625,93.30166666666666,93.30166666666666,188.70000000000002 +93.35111111111111,-68.17777777777778,70.8,93.35111111111111,93.35111111111111,188.8 +93.40055555555556,-68.21388888888889,70.83749999999999,93.40055555555556,93.40055555555556,188.9 +93.45,-68.25,70.875,93.45,93.45,189.0 +93.49944444444445,-68.28611111111111,70.9125,93.49944444444445,93.49944444444445,189.10000000000002 +93.54888888888888,-68.32222222222222,70.95,93.54888888888888,93.54888888888888,189.20000000000002 +93.59833333333333,-68.35833333333332,70.9875,93.59833333333333,93.59833333333333,189.3 +93.64777777777778,-68.39444444444443,71.02499999999999,93.64777777777778,93.64777777777778,189.4 +93.69722222222222,-68.43055555555554,71.0625,93.69722222222222,93.69722222222222,189.5 +93.74666666666667,-68.46666666666665,71.1,93.74666666666667,93.74666666666667,189.60000000000002 +93.79611111111112,-68.50277777777777,71.1375,93.79611111111112,93.79611111111112,189.70000000000002 +93.84555555555555,-68.53888888888888,71.175,93.84555555555555,93.84555555555555,189.8 +93.895,-68.57499999999999,71.21249999999999,93.895,93.895,189.9 +93.94444444444444,-68.6111111111111,71.25,93.94444444444444,93.94444444444444,190.0 +93.99388888888889,-68.64722222222221,71.2875,93.99388888888889,93.99388888888889,190.10000000000002 +94.04333333333334,-68.68333333333332,71.325,94.04333333333334,94.04333333333334,190.20000000000002 +94.09277777777777,-68.71944444444443,71.3625,94.09277777777777,94.09277777777777,190.3 +94.14222222222222,-68.75555555555555,71.39999999999999,94.14222222222222,94.14222222222222,190.4 +94.19166666666666,-68.79166666666666,71.4375,94.19166666666666,94.19166666666666,190.5 +94.24111111111111,-68.82777777777777,71.475,94.24111111111111,94.24111111111111,190.60000000000002 +94.29055555555556,-68.86388888888888,71.5125,94.29055555555556,94.29055555555556,190.70000000000002 +94.34,-68.89999999999999,71.55,94.34,94.34,190.8 +94.38944444444444,-68.9361111111111,71.58749999999999,94.38944444444444,94.38944444444444,190.9 +94.43888888888888,-68.97222222222221,71.625,94.43888888888888,94.43888888888888,191.0 +94.48833333333333,-69.00833333333333,71.6625,94.48833333333333,94.48833333333333,191.10000000000002 +94.53777777777778,-69.04444444444444,71.7,94.53777777777778,94.53777777777778,191.20000000000002 +94.58722222222222,-69.08055555555555,71.7375,94.58722222222222,94.58722222222222,191.3 +94.63666666666667,-69.11666666666666,71.77499999999999,94.63666666666667,94.63666666666667,191.4 +94.6861111111111,-69.15277777777777,71.8125,94.6861111111111,94.6861111111111,191.5 +94.73555555555555,-69.18888888888888,71.85,94.73555555555555,94.73555555555555,191.60000000000002 +94.785,-69.225,71.8875,94.785,94.785,191.70000000000002 +94.83444444444444,-69.2611111111111,71.925,94.83444444444444,94.83444444444444,191.8 +94.88388888888889,-69.29722222222222,71.96249999999999,94.88388888888889,94.88388888888889,191.9 +94.93333333333334,-69.33333333333333,72.0,94.93333333333334,94.93333333333334,192.0 +94.98277777777777,-69.36944444444444,72.0375,94.98277777777777,94.98277777777777,192.10000000000002 +95.03222222222222,-69.40555555555555,72.075,95.03222222222222,95.03222222222222,192.20000000000002 +95.08166666666666,-69.44166666666666,72.1125,95.08166666666666,95.08166666666666,192.3 +95.13111111111111,-69.47777777777777,72.14999999999999,95.13111111111111,95.13111111111111,192.4 +95.18055555555556,-69.51388888888889,72.1875,95.18055555555556,95.18055555555556,192.5 +95.23,-69.55,72.225,95.23,95.23,192.60000000000002 +95.27944444444444,-69.58611111111111,72.2625,95.27944444444444,95.27944444444444,192.70000000000002 +95.32888888888888,-69.62222222222222,72.3,95.32888888888888,95.32888888888888,192.8 +95.37833333333333,-69.65833333333333,72.33749999999999,95.37833333333333,95.37833333333333,192.9 +95.42777777777778,-69.69444444444444,72.375,95.42777777777778,95.42777777777778,193.0 +95.47722222222222,-69.73055555555555,72.4125,95.47722222222222,95.47722222222222,193.10000000000002 +95.52666666666667,-69.76666666666667,72.45,95.52666666666667,95.52666666666667,193.20000000000002 +95.5761111111111,-69.80277777777778,72.4875,95.5761111111111,95.5761111111111,193.3 +95.62555555555555,-69.83888888888889,72.52499999999999,95.62555555555555,95.62555555555555,193.4 +95.675,-69.875,72.5625,95.675,95.675,193.5 +95.72444444444444,-69.91111111111111,72.6,95.72444444444444,95.72444444444444,193.60000000000002 +95.77388888888889,-69.94722222222221,72.6375,95.77388888888889,95.77388888888889,193.70000000000002 +95.82333333333334,-69.98333333333332,72.675,95.82333333333334,95.82333333333334,193.8 +95.87277777777777,-70.01944444444443,72.71249999999999,95.87277777777777,95.87277777777777,193.9 +95.92222222222222,-70.05555555555554,72.75,95.92222222222222,95.92222222222222,194.0 +95.97166666666666,-70.09166666666665,72.7875,95.97166666666666,95.97166666666666,194.10000000000002 +96.02111111111111,-70.12777777777777,72.825,96.02111111111111,96.02111111111111,194.20000000000002 +96.07055555555556,-70.16388888888888,72.8625,96.07055555555556,96.07055555555556,194.3 +96.12,-70.19999999999999,72.89999999999999,96.12,96.12,194.4 +96.16944444444444,-70.2361111111111,72.9375,96.16944444444444,96.16944444444444,194.5 +96.21888888888888,-70.27222222222221,72.975,96.21888888888888,96.21888888888888,194.60000000000002 +96.26833333333333,-70.30833333333332,73.0125,96.26833333333333,96.26833333333333,194.70000000000002 +96.31777777777778,-70.34444444444443,73.05,96.31777777777778,96.31777777777778,194.8 +96.36722222222222,-70.38055555555555,73.08749999999999,96.36722222222222,96.36722222222222,194.9 +96.41666666666667,-70.41666666666666,73.125,96.41666666666667,96.41666666666667,195.0 +96.4661111111111,-70.45277777777777,73.1625,96.4661111111111,96.4661111111111,195.10000000000002 +96.51555555555555,-70.48888888888888,73.2,96.51555555555555,96.51555555555555,195.20000000000002 +96.565,-70.52499999999999,73.2375,96.565,96.565,195.3 +96.61444444444444,-70.5611111111111,73.27499999999999,96.61444444444444,96.61444444444444,195.4 +96.66388888888889,-70.59722222222221,73.3125,96.66388888888889,96.66388888888889,195.5 +96.71333333333334,-70.63333333333333,73.35,96.71333333333334,96.71333333333334,195.60000000000002 +96.76277777777777,-70.66944444444444,73.3875,96.76277777777777,96.76277777777777,195.70000000000002 +96.81222222222222,-70.70555555555555,73.425,96.81222222222222,96.81222222222222,195.8 +96.86166666666666,-70.74166666666666,73.46249999999999,96.86166666666666,96.86166666666666,195.9 +96.91111111111111,-70.77777777777777,73.5,96.91111111111111,96.91111111111111,196.0 +96.96055555555556,-70.81388888888888,73.5375,96.96055555555556,96.96055555555556,196.10000000000002 +97.01,-70.85,73.575,97.01,97.01,196.20000000000002 +97.05944444444444,-70.8861111111111,73.6125,97.05944444444444,97.05944444444444,196.3 +97.10888888888888,-70.92222222222222,73.64999999999999,97.10888888888888,97.10888888888888,196.4 +97.15833333333333,-70.95833333333333,73.6875,97.15833333333333,97.15833333333333,196.5 +97.20777777777778,-70.99444444444444,73.725,97.20777777777778,97.20777777777778,196.60000000000002 +97.25722222222223,-71.03055555555555,73.7625,97.25722222222223,97.25722222222223,196.70000000000002 +97.30666666666667,-71.06666666666666,73.8,97.30666666666667,97.30666666666667,196.8 +97.3561111111111,-71.10277777777777,73.83749999999999,97.3561111111111,97.3561111111111,196.9 +97.40555555555555,-71.13888888888889,73.875,97.40555555555555,97.40555555555555,197.0 +97.455,-71.175,73.9125,97.455,97.455,197.10000000000002 +97.50444444444445,-71.21111111111111,73.95,97.50444444444445,97.50444444444445,197.20000000000002 +97.55388888888889,-71.24722222222222,73.9875,97.55388888888889,97.55388888888889,197.3 +97.60333333333334,-71.28333333333333,74.02499999999999,97.60333333333334,97.60333333333334,197.4 +97.65277777777777,-71.31944444444444,74.0625,97.65277777777777,97.65277777777777,197.5 +97.70222222222222,-71.35555555555555,74.1,97.70222222222222,97.70222222222222,197.60000000000002 +97.75166666666667,-71.39166666666667,74.1375,97.75166666666667,97.75166666666667,197.70000000000002 +97.80111111111111,-71.42777777777778,74.175,97.80111111111111,97.80111111111111,197.8 +97.85055555555556,-71.46388888888889,74.21249999999999,97.85055555555556,97.85055555555556,197.9 +97.89999999999999,-71.5,74.25,97.89999999999999,97.89999999999999,198.0 +97.94944444444444,-71.53611111111111,74.2875,97.94944444444444,97.94944444444444,198.10000000000002 +97.99888888888889,-71.57222222222221,74.325,97.99888888888889,97.99888888888889,198.20000000000002 +98.04833333333333,-71.60833333333332,74.3625,98.04833333333333,98.04833333333333,198.3 +98.09777777777778,-71.64444444444443,74.39999999999999,98.09777777777778,98.09777777777778,198.4 +98.14722222222223,-71.68055555555554,74.4375,98.14722222222223,98.14722222222223,198.5 +98.19666666666666,-71.71666666666665,74.475,98.19666666666666,98.19666666666666,198.60000000000002 +98.2461111111111,-71.75277777777777,74.5125,98.2461111111111,98.2461111111111,198.70000000000002 +98.29555555555555,-71.78888888888888,74.55,98.29555555555555,98.29555555555555,198.8 +98.345,-71.82499999999999,74.58749999999999,98.345,98.345,198.9 +98.39444444444445,-71.8611111111111,74.625,98.39444444444445,98.39444444444445,199.0 +98.44388888888889,-71.89722222222221,74.6625,98.44388888888889,98.44388888888889,199.10000000000002 +98.49333333333333,-71.93333333333332,74.7,98.49333333333333,98.49333333333333,199.20000000000002 +98.54277777777777,-71.96944444444443,74.7375,98.54277777777777,98.54277777777777,199.3 +98.59222222222222,-72.00555555555555,74.77499999999999,98.59222222222222,98.59222222222222,199.4 +98.64166666666667,-72.04166666666666,74.8125,98.64166666666667,98.64166666666667,199.5 +98.69111111111111,-72.07777777777777,74.85,98.69111111111111,98.69111111111111,199.60000000000002 +98.74055555555556,-72.11388888888888,74.8875,98.74055555555556,98.74055555555556,199.70000000000002 +98.78999999999999,-72.14999999999999,74.925,98.78999999999999,98.78999999999999,199.8 +98.83944444444444,-72.1861111111111,74.96249999999999,98.83944444444444,98.83944444444444,199.9 +98.88888888888889,-72.22222222222221,75.0,98.88888888888889,98.88888888888889,200.0 +98.93833333333333,-72.25833333333333,75.0375,98.93833333333333,98.93833333333333,200.10000000000002 +98.98777777777778,-72.29444444444444,75.075,98.98777777777778,98.98777777777778,200.20000000000002 +99.03722222222223,-72.33055555555555,75.1125,99.03722222222223,99.03722222222223,200.3 +99.08666666666666,-72.36666666666666,75.14999999999999,99.08666666666666,99.08666666666666,200.4 +99.1361111111111,-72.40277777777777,75.1875,99.1361111111111,99.1361111111111,200.5 +99.18555555555555,-72.43888888888888,75.225,99.18555555555555,99.18555555555555,200.60000000000002 +99.235,-72.475,75.2625,99.235,99.235,200.70000000000002 +99.28444444444445,-72.5111111111111,75.3,99.28444444444445,99.28444444444445,200.8 +99.3338888888889,-72.54722222222222,75.33749999999999,99.3338888888889,99.3338888888889,200.9 +99.38333333333333,-72.58333333333333,75.375,99.38333333333333,99.38333333333333,201.0 +99.43277777777777,-72.61944444444444,75.4125,99.43277777777777,99.43277777777777,201.10000000000002 +99.48222222222222,-72.65555555555555,75.45,99.48222222222222,99.48222222222222,201.20000000000002 +99.53166666666667,-72.69166666666666,75.4875,99.53166666666667,99.53166666666667,201.3 +99.58111111111111,-72.72777777777777,75.52499999999999,99.58111111111111,99.58111111111111,201.4 +99.63055555555556,-72.76388888888889,75.5625,99.63055555555556,99.63055555555556,201.5 +99.67999999999999,-72.8,75.6,99.67999999999999,99.67999999999999,201.60000000000002 +99.72944444444444,-72.83611111111111,75.6375,99.72944444444444,99.72944444444444,201.70000000000002 +99.77888888888889,-72.87222222222222,75.675,99.77888888888889,99.77888888888889,201.8 +99.82833333333333,-72.90833333333333,75.71249999999999,99.82833333333333,99.82833333333333,201.9 +99.87777777777778,-72.94444444444444,75.75,99.87777777777778,99.87777777777778,202.0 +99.92722222222223,-72.98055555555555,75.7875,99.92722222222223,99.92722222222223,202.10000000000002 +99.97666666666666,-73.01666666666667,75.825,99.97666666666666,99.97666666666666,202.20000000000002 +100.0261111111111,-73.05277777777778,75.8625,100.0261111111111,100.0261111111111,202.3 +100.07555555555555,-73.08888888888889,75.89999999999999,100.07555555555555,100.07555555555555,202.4 +100.125,-73.125,75.9375,100.125,100.125,202.5 +100.17444444444445,-73.1611111111111,75.975,100.17444444444445,100.17444444444445,202.60000000000002 +100.2238888888889,-73.19722222222221,76.0125,100.2238888888889,100.2238888888889,202.70000000000002 +100.27333333333333,-73.23333333333332,76.05,100.27333333333333,100.27333333333333,202.8 +100.32277777777777,-73.26944444444443,76.08749999999999,100.32277777777777,100.32277777777777,202.9 +100.37222222222222,-73.30555555555554,76.125,100.37222222222222,100.37222222222222,203.0 +100.42166666666667,-73.34166666666665,76.1625,100.42166666666667,100.42166666666667,203.10000000000002 +100.47111111111111,-73.37777777777777,76.2,100.47111111111111,100.47111111111111,203.20000000000002 +100.52055555555556,-73.41388888888888,76.2375,100.52055555555556,100.52055555555556,203.3 +100.57,-73.44999999999999,76.27499999999999,100.57,100.57,203.4 +100.61944444444444,-73.4861111111111,76.3125,100.61944444444444,100.61944444444444,203.5 +100.66888888888889,-73.52222222222221,76.35,100.66888888888889,100.66888888888889,203.60000000000002 +100.71833333333333,-73.55833333333332,76.3875,100.71833333333333,100.71833333333333,203.70000000000002 +100.76777777777778,-73.59444444444443,76.425,100.76777777777778,100.76777777777778,203.8 +100.81722222222223,-73.63055555555555,76.46249999999999,100.81722222222223,100.81722222222223,203.9 +100.86666666666666,-73.66666666666666,76.5,100.86666666666666,100.86666666666666,204.0 +100.9161111111111,-73.70277777777777,76.5375,100.9161111111111,100.9161111111111,204.10000000000002 +100.96555555555555,-73.73888888888888,76.575,100.96555555555555,100.96555555555555,204.20000000000002 +101.015,-73.77499999999999,76.6125,101.015,101.015,204.3 +101.06444444444445,-73.8111111111111,76.64999999999999,101.06444444444445,101.06444444444445,204.4 +101.1138888888889,-73.84722222222221,76.6875,101.1138888888889,101.1138888888889,204.5 +101.16333333333333,-73.88333333333333,76.725,101.16333333333333,101.16333333333333,204.60000000000002 +101.21277777777777,-73.91944444444444,76.7625,101.21277777777777,101.21277777777777,204.70000000000002 +101.26222222222222,-73.95555555555555,76.8,101.26222222222222,101.26222222222222,204.8 +101.31166666666667,-73.99166666666666,76.83749999999999,101.31166666666667,101.31166666666667,204.9 +101.36111111111111,-74.02777777777777,76.875,101.36111111111111,101.36111111111111,205.0 +101.41055555555555,-74.06388888888888,76.9125,101.41055555555555,101.41055555555555,205.10000000000002 +101.46,-74.1,76.95,101.46,101.46,205.20000000000002 +101.50944444444444,-74.1361111111111,76.9875,101.50944444444444,101.50944444444444,205.3 +101.55888888888889,-74.17222222222222,77.02499999999999,101.55888888888889,101.55888888888889,205.4 +101.60833333333333,-74.20833333333333,77.0625,101.60833333333333,101.60833333333333,205.5 +101.65777777777778,-74.24444444444444,77.1,101.65777777777778,101.65777777777778,205.60000000000002 +101.70722222222221,-74.28055555555555,77.1375,101.70722222222221,101.70722222222221,205.70000000000002 +101.75666666666666,-74.31666666666666,77.175,101.75666666666666,101.75666666666666,205.8 +101.80611111111111,-74.35277777777777,77.21249999999999,101.80611111111111,101.80611111111111,205.9 +101.85555555555555,-74.38888888888889,77.25,101.85555555555555,101.85555555555555,206.0 +101.905,-74.425,77.2875,101.905,101.905,206.10000000000002 +101.95444444444445,-74.46111111111111,77.325,101.95444444444445,101.95444444444445,206.20000000000002 +102.00388888888888,-74.49722222222222,77.3625,102.00388888888888,102.00388888888888,206.3 +102.05333333333333,-74.53333333333333,77.39999999999999,102.05333333333333,102.05333333333333,206.4 +102.10277777777777,-74.56944444444444,77.4375,102.10277777777777,102.10277777777777,206.5 +102.15222222222222,-74.60555555555555,77.475,102.15222222222222,102.15222222222222,206.60000000000002 +102.20166666666667,-74.64166666666667,77.5125,102.20166666666667,102.20166666666667,206.70000000000002 +102.25111111111111,-74.67777777777778,77.55,102.25111111111111,102.25111111111111,206.8 +102.30055555555555,-74.71388888888889,77.58749999999999,102.30055555555555,102.30055555555555,206.9 +102.35,-74.75,77.625,102.35,102.35,207.0 +102.39944444444444,-74.7861111111111,77.6625,102.39944444444444,102.39944444444444,207.10000000000002 +102.44888888888889,-74.82222222222221,77.7,102.44888888888889,102.44888888888889,207.20000000000002 +102.49833333333333,-74.85833333333332,77.7375,102.49833333333333,102.49833333333333,207.3 +102.54777777777778,-74.89444444444443,77.77499999999999,102.54777777777778,102.54777777777778,207.4 +102.59722222222221,-74.93055555555554,77.8125,102.59722222222221,102.59722222222221,207.5 +102.64666666666666,-74.96666666666665,77.85,102.64666666666666,102.64666666666666,207.60000000000002 +102.69611111111111,-75.00277777777777,77.8875,102.69611111111111,102.69611111111111,207.70000000000002 +102.74555555555555,-75.03888888888888,77.925,102.74555555555555,102.74555555555555,207.8 +102.795,-75.07499999999999,77.96249999999999,102.795,102.795,207.9 +102.84444444444445,-75.1111111111111,78.0,102.84444444444445,102.84444444444445,208.0 +102.89388888888888,-75.14722222222221,78.0375,102.89388888888888,102.89388888888888,208.10000000000002 +102.94333333333333,-75.18333333333332,78.075,102.94333333333333,102.94333333333333,208.20000000000002 +102.99277777777777,-75.21944444444443,78.1125,102.99277777777777,102.99277777777777,208.3 +103.04222222222222,-75.25555555555555,78.14999999999999,103.04222222222222,103.04222222222222,208.4 +103.09166666666667,-75.29166666666666,78.1875,103.09166666666667,103.09166666666667,208.5 +103.14111111111112,-75.32777777777777,78.225,103.14111111111112,103.14111111111112,208.60000000000002 +103.19055555555555,-75.36388888888888,78.2625,103.19055555555555,103.19055555555555,208.70000000000002 +103.24,-75.39999999999999,78.3,103.24,103.24,208.8 +103.28944444444444,-75.4361111111111,78.33749999999999,103.28944444444444,103.28944444444444,208.9 +103.33888888888889,-75.47222222222221,78.375,103.33888888888889,103.33888888888889,209.0 +103.38833333333334,-75.50833333333333,78.4125,103.38833333333334,103.38833333333334,209.10000000000002 +103.43777777777778,-75.54444444444444,78.45,103.43777777777778,103.43777777777778,209.20000000000002 +103.48722222222221,-75.58055555555555,78.4875,103.48722222222221,103.48722222222221,209.3 +103.53666666666666,-75.61666666666666,78.52499999999999,103.53666666666666,103.53666666666666,209.4 +103.58611111111111,-75.65277777777777,78.5625,103.58611111111111,103.58611111111111,209.5 +103.63555555555556,-75.68888888888888,78.6,103.63555555555556,103.63555555555556,209.60000000000002 +103.685,-75.725,78.6375,103.685,103.685,209.70000000000002 +103.73444444444445,-75.7611111111111,78.675,103.73444444444445,103.73444444444445,209.8 +103.78388888888888,-75.79722222222222,78.71249999999999,103.78388888888888,103.78388888888888,209.9 +103.83333333333333,-75.83333333333333,78.75,103.83333333333333,103.83333333333333,210.0 +103.88277777777778,-75.86944444444444,78.7875,103.88277777777778,103.88277777777778,210.10000000000002 +103.93222222222222,-75.90555555555555,78.825,103.93222222222222,103.93222222222222,210.20000000000002 +103.98166666666667,-75.94166666666666,78.8625,103.98166666666667,103.98166666666667,210.3 +104.03111111111112,-75.97777777777777,78.89999999999999,104.03111111111112,104.03111111111112,210.4 +104.08055555555555,-76.01388888888889,78.9375,104.08055555555555,104.08055555555555,210.5 +104.13,-76.05,78.975,104.13,104.13,210.60000000000002 +104.17944444444444,-76.08611111111111,79.0125,104.17944444444444,104.17944444444444,210.70000000000002 +104.22888888888889,-76.12222222222222,79.05,104.22888888888889,104.22888888888889,210.8 +104.27833333333334,-76.15833333333333,79.08749999999999,104.27833333333334,104.27833333333334,210.9 +104.32777777777778,-76.19444444444444,79.125,104.32777777777778,104.32777777777778,211.0 +104.37722222222222,-76.23055555555555,79.1625,104.37722222222222,104.37722222222222,211.10000000000002 +104.42666666666666,-76.26666666666667,79.2,104.42666666666666,104.42666666666666,211.20000000000002 +104.47611111111111,-76.30277777777778,79.2375,104.47611111111111,104.47611111111111,211.3 +104.52555555555556,-76.33888888888889,79.27499999999999,104.52555555555556,104.52555555555556,211.4 +104.575,-76.37499999999999,79.3125,104.575,104.575,211.5 +104.62444444444445,-76.4111111111111,79.35,104.62444444444445,104.62444444444445,211.60000000000002 +104.67388888888888,-76.44722222222221,79.3875,104.67388888888888,104.67388888888888,211.70000000000002 +104.72333333333333,-76.48333333333332,79.425,104.72333333333333,104.72333333333333,211.8 +104.77277777777778,-76.51944444444443,79.46249999999999,104.77277777777778,104.77277777777778,211.9 +104.82222222222222,-76.55555555555554,79.5,104.82222222222222,104.82222222222222,212.0 +104.87166666666667,-76.59166666666665,79.5375,104.87166666666667,104.87166666666667,212.10000000000002 +104.9211111111111,-76.62777777777777,79.575,104.9211111111111,104.9211111111111,212.20000000000002 +104.97055555555555,-76.66388888888888,79.6125,104.97055555555555,104.97055555555555,212.3 +105.02,-76.69999999999999,79.64999999999999,105.02,105.02,212.4 +105.06944444444444,-76.7361111111111,79.6875,105.06944444444444,105.06944444444444,212.5 +105.11888888888889,-76.77222222222221,79.725,105.11888888888889,105.11888888888889,212.60000000000002 +105.16833333333334,-76.80833333333332,79.7625,105.16833333333334,105.16833333333334,212.70000000000002 +105.21777777777777,-76.84444444444443,79.8,105.21777777777777,105.21777777777777,212.8 +105.26722222222222,-76.88055555555555,79.83749999999999,105.26722222222222,105.26722222222222,212.9 +105.31666666666666,-76.91666666666666,79.875,105.31666666666666,105.31666666666666,213.0 +105.36611111111111,-76.95277777777777,79.9125,105.36611111111111,105.36611111111111,213.10000000000002 +105.41555555555556,-76.98888888888888,79.95,105.41555555555556,105.41555555555556,213.20000000000002 +105.465,-77.02499999999999,79.9875,105.465,105.465,213.3 +105.51444444444444,-77.0611111111111,80.02499999999999,105.51444444444444,105.51444444444444,213.4 +105.56388888888888,-77.09722222222221,80.0625,105.56388888888888,105.56388888888888,213.5 +105.61333333333333,-77.13333333333333,80.1,105.61333333333333,105.61333333333333,213.60000000000002 +105.66277777777778,-77.16944444444444,80.1375,105.66277777777778,105.66277777777778,213.70000000000002 +105.71222222222222,-77.20555555555555,80.175,105.71222222222222,105.71222222222222,213.8 +105.76166666666667,-77.24166666666666,80.21249999999999,105.76166666666667,105.76166666666667,213.9 +105.8111111111111,-77.27777777777777,80.25,105.8111111111111,105.8111111111111,214.0 +105.86055555555555,-77.31388888888888,80.2875,105.86055555555555,105.86055555555555,214.10000000000002 +105.91,-77.35,80.325,105.91,105.91,214.20000000000002 +105.95944444444444,-77.3861111111111,80.3625,105.95944444444444,105.95944444444444,214.3 +106.00888888888889,-77.42222222222222,80.39999999999999,106.00888888888889,106.00888888888889,214.4 +106.05833333333334,-77.45833333333333,80.4375,106.05833333333334,106.05833333333334,214.5 +106.10777777777777,-77.49444444444444,80.475,106.10777777777777,106.10777777777777,214.60000000000002 +106.15722222222222,-77.53055555555555,80.5125,106.15722222222222,106.15722222222222,214.70000000000002 +106.20666666666666,-77.56666666666666,80.55,106.20666666666666,106.20666666666666,214.8 +106.25611111111111,-77.60277777777777,80.58749999999999,106.25611111111111,106.25611111111111,214.9 +106.30555555555556,-77.63888888888889,80.625,106.30555555555556,106.30555555555556,215.0 +106.355,-77.675,80.6625,106.355,106.355,215.10000000000002 +106.40444444444444,-77.71111111111111,80.7,106.40444444444444,106.40444444444444,215.20000000000002 +106.45388888888888,-77.74722222222222,80.7375,106.45388888888888,106.45388888888888,215.3 +106.50333333333333,-77.78333333333333,80.77499999999999,106.50333333333333,106.50333333333333,215.4 +106.55277777777778,-77.81944444444444,80.8125,106.55277777777778,106.55277777777778,215.5 +106.60222222222222,-77.85555555555555,80.85,106.60222222222222,106.60222222222222,215.60000000000002 +106.65166666666667,-77.89166666666667,80.8875,106.65166666666667,106.65166666666667,215.70000000000002 +106.7011111111111,-77.92777777777778,80.925,106.7011111111111,106.7011111111111,215.8 +106.75055555555555,-77.96388888888889,80.96249999999999,106.75055555555555,106.75055555555555,215.9 +106.8,-77.99999999999999,81.0,106.8,106.8,216.0 +106.84944444444444,-78.0361111111111,81.0375,106.84944444444444,106.84944444444444,216.10000000000002 +106.89888888888889,-78.07222222222221,81.075,106.89888888888889,106.89888888888889,216.20000000000002 +106.94833333333334,-78.10833333333332,81.1125,106.94833333333334,106.94833333333334,216.3 +106.99777777777777,-78.14444444444443,81.14999999999999,106.99777777777777,106.99777777777777,216.4 +107.04722222222222,-78.18055555555554,81.1875,107.04722222222222,107.04722222222222,216.5 +107.09666666666666,-78.21666666666665,81.225,107.09666666666666,107.09666666666666,216.60000000000002 +107.14611111111111,-78.25277777777777,81.2625,107.14611111111111,107.14611111111111,216.70000000000002 +107.19555555555556,-78.28888888888888,81.3,107.19555555555556,107.19555555555556,216.8 +107.245,-78.32499999999999,81.33749999999999,107.245,107.245,216.9 +107.29444444444444,-78.3611111111111,81.375,107.29444444444444,107.29444444444444,217.0 +107.34388888888888,-78.39722222222221,81.4125,107.34388888888888,107.34388888888888,217.10000000000002 +107.39333333333333,-78.43333333333332,81.45,107.39333333333333,107.39333333333333,217.20000000000002 +107.44277777777778,-78.46944444444443,81.4875,107.44277777777778,107.44277777777778,217.3 +107.49222222222222,-78.50555555555555,81.52499999999999,107.49222222222222,107.49222222222222,217.4 +107.54166666666667,-78.54166666666666,81.5625,107.54166666666667,107.54166666666667,217.5 +107.5911111111111,-78.57777777777777,81.6,107.5911111111111,107.5911111111111,217.60000000000002 +107.64055555555555,-78.61388888888888,81.6375,107.64055555555555,107.64055555555555,217.70000000000002 +107.69,-78.64999999999999,81.675,107.69,107.69,217.8 +107.73944444444444,-78.6861111111111,81.71249999999999,107.73944444444444,107.73944444444444,217.9 +107.78888888888889,-78.72222222222221,81.75,107.78888888888889,107.78888888888889,218.0 +107.83833333333334,-78.75833333333333,81.7875,107.83833333333334,107.83833333333334,218.10000000000002 +107.88777777777777,-78.79444444444444,81.825,107.88777777777777,107.88777777777777,218.20000000000002 +107.93722222222222,-78.83055555555555,81.8625,107.93722222222222,107.93722222222222,218.3 +107.98666666666666,-78.86666666666666,81.89999999999999,107.98666666666666,107.98666666666666,218.4 +108.03611111111111,-78.90277777777777,81.9375,108.03611111111111,108.03611111111111,218.5 +108.08555555555556,-78.93888888888888,81.975,108.08555555555556,108.08555555555556,218.60000000000002 +108.135,-78.975,82.0125,108.135,108.135,218.70000000000002 +108.18444444444444,-79.0111111111111,82.05,108.18444444444444,108.18444444444444,218.8 +108.23388888888888,-79.04722222222222,82.08749999999999,108.23388888888888,108.23388888888888,218.9 +108.28333333333333,-79.08333333333333,82.125,108.28333333333333,108.28333333333333,219.0 +108.33277777777778,-79.11944444444444,82.1625,108.33277777777778,108.33277777777778,219.10000000000002 +108.38222222222223,-79.15555555555555,82.2,108.38222222222223,108.38222222222223,219.20000000000002 +108.43166666666667,-79.19166666666666,82.2375,108.43166666666667,108.43166666666667,219.3 +108.4811111111111,-79.22777777777777,82.27499999999999,108.4811111111111,108.4811111111111,219.4 +108.53055555555555,-79.26388888888889,82.3125,108.53055555555555,108.53055555555555,219.5 +108.58,-79.3,82.35,108.58,108.58,219.60000000000002 +108.62944444444445,-79.33611111111111,82.3875,108.62944444444445,108.62944444444445,219.70000000000002 +108.67888888888889,-79.37222222222222,82.425,108.67888888888889,108.67888888888889,219.8 +108.72833333333332,-79.40833333333333,82.46249999999999,108.72833333333332,108.72833333333332,219.9 +108.77777777777777,-79.44444444444444,82.5,108.77777777777777,108.77777777777777,220.0 +108.82722222222222,-79.48055555555555,82.5375,108.82722222222222,108.82722222222222,220.10000000000002 +108.87666666666667,-79.51666666666667,82.575,108.87666666666667,108.87666666666667,220.20000000000002 +108.92611111111111,-79.55277777777778,82.6125,108.92611111111111,108.92611111111111,220.3 +108.97555555555556,-79.58888888888887,82.64999999999999,108.97555555555556,108.97555555555556,220.4 +109.02499999999999,-79.62499999999999,82.6875,109.02499999999999,109.02499999999999,220.5 +109.07444444444444,-79.6611111111111,82.725,109.07444444444444,109.07444444444444,220.60000000000002 +109.12388888888889,-79.69722222222221,82.7625,109.12388888888889,109.12388888888889,220.70000000000002 +109.17333333333333,-79.73333333333332,82.8,109.17333333333333,109.17333333333333,220.8 +109.22277777777778,-79.76944444444443,82.83749999999999,109.22277777777778,109.22277777777778,220.9 +109.27222222222223,-79.80555555555554,82.875,109.27222222222223,109.27222222222223,221.0 +109.32166666666666,-79.84166666666665,82.9125,109.32166666666666,109.32166666666666,221.10000000000002 +109.3711111111111,-79.87777777777777,82.95,109.3711111111111,109.3711111111111,221.20000000000002 +109.42055555555555,-79.91388888888888,82.9875,109.42055555555555,109.42055555555555,221.3 +109.47,-79.94999999999999,83.02499999999999,109.47,109.47,221.4 +109.51944444444445,-79.9861111111111,83.0625,109.51944444444445,109.51944444444445,221.5 +109.56888888888889,-80.02222222222221,83.1,109.56888888888889,109.56888888888889,221.60000000000002 +109.61833333333333,-80.05833333333332,83.1375,109.61833333333333,109.61833333333333,221.70000000000002 +109.66777777777777,-80.09444444444443,83.175,109.66777777777777,109.66777777777777,221.8 +109.71722222222222,-80.13055555555555,83.21249999999999,109.71722222222222,109.71722222222222,221.9 +109.76666666666667,-80.16666666666666,83.25,109.76666666666667,109.76666666666667,222.0 +109.81611111111111,-80.20277777777777,83.2875,109.81611111111111,109.81611111111111,222.10000000000002 +109.86555555555556,-80.23888888888888,83.325,109.86555555555556,109.86555555555556,222.20000000000002 +109.91499999999999,-80.27499999999999,83.3625,109.91499999999999,109.91499999999999,222.3 +109.96444444444444,-80.3111111111111,83.39999999999999,109.96444444444444,109.96444444444444,222.4 +110.01388888888889,-80.34722222222221,83.4375,110.01388888888889,110.01388888888889,222.5 +110.06333333333333,-80.38333333333333,83.475,110.06333333333333,110.06333333333333,222.60000000000002 +110.11277777777778,-80.41944444444444,83.5125,110.11277777777778,110.11277777777778,222.70000000000002 +110.16222222222223,-80.45555555555555,83.55,110.16222222222223,110.16222222222223,222.8 +110.21166666666666,-80.49166666666666,83.58749999999999,110.21166666666666,110.21166666666666,222.9 +110.2611111111111,-80.52777777777777,83.625,110.2611111111111,110.2611111111111,223.0 +110.31055555555555,-80.56388888888888,83.6625,110.31055555555555,110.31055555555555,223.10000000000002 +110.36,-80.6,83.7,110.36,110.36,223.20000000000002 +110.40944444444445,-80.6361111111111,83.7375,110.40944444444445,110.40944444444445,223.3 +110.4588888888889,-80.67222222222222,83.77499999999999,110.4588888888889,110.4588888888889,223.4 +110.50833333333333,-80.70833333333333,83.8125,110.50833333333333,110.50833333333333,223.5 +110.55777777777777,-80.74444444444444,83.85,110.55777777777777,110.55777777777777,223.60000000000002 +110.60722222222222,-80.78055555555555,83.8875,110.60722222222222,110.60722222222222,223.70000000000002 +110.65666666666667,-80.81666666666666,83.925,110.65666666666667,110.65666666666667,223.8 +110.70611111111111,-80.85277777777777,83.96249999999999,110.70611111111111,110.70611111111111,223.9 +110.75555555555556,-80.88888888888889,84.0,110.75555555555556,110.75555555555556,224.0 +110.80499999999999,-80.925,84.0375,110.80499999999999,110.80499999999999,224.10000000000002 +110.85444444444444,-80.96111111111111,84.075,110.85444444444444,110.85444444444444,224.20000000000002 +110.90388888888889,-80.99722222222222,84.1125,110.90388888888889,110.90388888888889,224.3 +110.95333333333333,-81.03333333333333,84.14999999999999,110.95333333333333,110.95333333333333,224.4 +111.00277777777778,-81.06944444444444,84.1875,111.00277777777778,111.00277777777778,224.5 +111.05222222222223,-81.10555555555555,84.225,111.05222222222223,111.05222222222223,224.60000000000002 +111.10166666666666,-81.14166666666667,84.2625,111.10166666666666,111.10166666666666,224.70000000000002 +111.1511111111111,-81.17777777777778,84.3,111.1511111111111,111.1511111111111,224.8 +111.20055555555555,-81.21388888888887,84.33749999999999,111.20055555555555,111.20055555555555,224.9 +111.25,-81.24999999999999,84.375,111.25,111.25,225.0 +111.29944444444445,-81.2861111111111,84.4125,111.29944444444445,111.29944444444445,225.10000000000002 +111.3488888888889,-81.32222222222221,84.45,111.3488888888889,111.3488888888889,225.20000000000002 +111.39833333333333,-81.35833333333332,84.4875,111.39833333333333,111.39833333333333,225.3 +111.44777777777777,-81.39444444444443,84.52499999999999,111.44777777777777,111.44777777777777,225.4 +111.49722222222222,-81.43055555555554,84.5625,111.49722222222222,111.49722222222222,225.5 +111.54666666666667,-81.46666666666665,84.6,111.54666666666667,111.54666666666667,225.60000000000002 +111.59611111111111,-81.50277777777777,84.6375,111.59611111111111,111.59611111111111,225.70000000000002 +111.64555555555556,-81.53888888888888,84.675,111.64555555555556,111.64555555555556,225.8 +111.695,-81.57499999999999,84.71249999999999,111.695,111.695,225.9 +111.74444444444444,-81.6111111111111,84.75,111.74444444444444,111.74444444444444,226.0 +111.79388888888889,-81.64722222222221,84.7875,111.79388888888889,111.79388888888889,226.10000000000002 +111.84333333333333,-81.68333333333332,84.825,111.84333333333333,111.84333333333333,226.20000000000002 +111.89277777777778,-81.71944444444443,84.8625,111.89277777777778,111.89277777777778,226.3 +111.94222222222223,-81.75555555555555,84.89999999999999,111.94222222222223,111.94222222222223,226.4 +111.99166666666666,-81.79166666666666,84.9375,111.99166666666666,111.99166666666666,226.5 +112.0411111111111,-81.82777777777777,84.975,112.0411111111111,112.0411111111111,226.60000000000002 +112.09055555555555,-81.86388888888888,85.0125,112.09055555555555,112.09055555555555,226.70000000000002 +112.14,-81.89999999999999,85.05,112.14,112.14,226.8 +112.18944444444445,-81.9361111111111,85.08749999999999,112.18944444444445,112.18944444444445,226.9 +112.23888888888888,-81.97222222222221,85.125,112.23888888888888,112.23888888888888,227.0 +112.28833333333333,-82.00833333333333,85.1625,112.28833333333333,112.28833333333333,227.10000000000002 +112.33777777777777,-82.04444444444444,85.2,112.33777777777777,112.33777777777777,227.20000000000002 +112.38722222222222,-82.08055555555555,85.2375,112.38722222222222,112.38722222222222,227.3 +112.43666666666667,-82.11666666666666,85.27499999999999,112.43666666666667,112.43666666666667,227.4 +112.48611111111111,-82.15277777777777,85.3125,112.48611111111111,112.48611111111111,227.5 +112.53555555555555,-82.18888888888888,85.35,112.53555555555555,112.53555555555555,227.60000000000002 +112.585,-82.225,85.3875,112.585,112.585,227.70000000000002 +112.63444444444444,-82.2611111111111,85.425,112.63444444444444,112.63444444444444,227.8 +112.68388888888889,-82.29722222222222,85.46249999999999,112.68388888888889,112.68388888888889,227.9 +112.73333333333333,-82.33333333333333,85.5,112.73333333333333,112.73333333333333,228.0 +112.78277777777778,-82.36944444444444,85.5375,112.78277777777778,112.78277777777778,228.10000000000002 +112.83222222222221,-82.40555555555555,85.575,112.83222222222221,112.83222222222221,228.20000000000002 +112.88166666666666,-82.44166666666666,85.6125,112.88166666666666,112.88166666666666,228.3 +112.93111111111111,-82.47777777777777,85.64999999999999,112.93111111111111,112.93111111111111,228.4 +112.98055555555555,-82.51388888888889,85.6875,112.98055555555555,112.98055555555555,228.5 +113.03,-82.55,85.725,113.03,113.03,228.60000000000002 +113.07944444444445,-82.58611111111111,85.7625,113.07944444444445,113.07944444444445,228.70000000000002 +113.12888888888888,-82.62222222222222,85.8,113.12888888888888,113.12888888888888,228.8 +113.17833333333333,-82.65833333333333,85.83749999999999,113.17833333333333,113.17833333333333,228.9 +113.22777777777777,-82.69444444444444,85.875,113.22777777777777,113.22777777777777,229.0 +113.27722222222222,-82.73055555555555,85.9125,113.27722222222222,113.27722222222222,229.10000000000002 +113.32666666666667,-82.76666666666667,85.95,113.32666666666667,113.32666666666667,229.20000000000002 +113.37611111111111,-82.80277777777776,85.9875,113.37611111111111,113.37611111111111,229.3 +113.42555555555555,-82.83888888888887,86.02499999999999,113.42555555555555,113.42555555555555,229.4 +113.475,-82.87499999999999,86.0625,113.475,113.475,229.5 +113.52444444444444,-82.9111111111111,86.1,113.52444444444444,113.52444444444444,229.60000000000002 +113.57388888888889,-82.94722222222221,86.1375,113.57388888888889,113.57388888888889,229.70000000000002 +113.62333333333333,-82.98333333333332,86.175,113.62333333333333,113.62333333333333,229.8 +113.67277777777778,-83.01944444444443,86.21249999999999,113.67277777777778,113.67277777777778,229.9 +113.72222222222221,-83.05555555555554,86.25,113.72222222222221,113.72222222222221,230.0 +113.77166666666666,-83.09166666666665,86.2875,113.77166666666666,113.77166666666666,230.10000000000002 +113.82111111111111,-83.12777777777777,86.325,113.82111111111111,113.82111111111111,230.20000000000002 +113.87055555555555,-83.16388888888888,86.3625,113.87055555555555,113.87055555555555,230.3 +113.92,-83.19999999999999,86.39999999999999,113.92,113.92,230.4 +113.96944444444445,-83.2361111111111,86.4375,113.96944444444445,113.96944444444445,230.5 +114.01888888888888,-83.27222222222221,86.475,114.01888888888888,114.01888888888888,230.60000000000002 +114.06833333333333,-83.30833333333332,86.5125,114.06833333333333,114.06833333333333,230.70000000000002 +114.11777777777777,-83.34444444444443,86.55,114.11777777777777,114.11777777777777,230.8 +114.16722222222222,-83.38055555555555,86.58749999999999,114.16722222222222,114.16722222222222,230.9 +114.21666666666667,-83.41666666666666,86.625,114.21666666666667,114.21666666666667,231.0 +114.26611111111112,-83.45277777777777,86.6625,114.26611111111112,114.26611111111112,231.10000000000002 +114.31555555555555,-83.48888888888888,86.7,114.31555555555555,114.31555555555555,231.20000000000002 +114.365,-83.52499999999999,86.7375,114.365,114.365,231.3 +114.41444444444444,-83.5611111111111,86.77499999999999,114.41444444444444,114.41444444444444,231.4 +114.46388888888889,-83.59722222222221,86.8125,114.46388888888889,114.46388888888889,231.5 +114.51333333333334,-83.63333333333333,86.85,114.51333333333334,114.51333333333334,231.60000000000002 +114.56277777777778,-83.66944444444444,86.8875,114.56277777777778,114.56277777777778,231.70000000000002 +114.61222222222221,-83.70555555555555,86.925,114.61222222222221,114.61222222222221,231.8 +114.66166666666666,-83.74166666666666,86.96249999999999,114.66166666666666,114.66166666666666,231.9 +114.71111111111111,-83.77777777777777,87.0,114.71111111111111,114.71111111111111,232.0 +114.76055555555556,-83.81388888888888,87.0375,114.76055555555556,114.76055555555556,232.10000000000002 +114.81,-83.85,87.075,114.81,114.81,232.20000000000002 +114.85944444444445,-83.8861111111111,87.1125,114.85944444444445,114.85944444444445,232.3 +114.90888888888888,-83.92222222222222,87.14999999999999,114.90888888888888,114.90888888888888,232.4 +114.95833333333333,-83.95833333333333,87.1875,114.95833333333333,114.95833333333333,232.5 +115.00777777777778,-83.99444444444444,87.225,115.00777777777778,115.00777777777778,232.60000000000002 +115.05722222222222,-84.03055555555555,87.2625,115.05722222222222,115.05722222222222,232.70000000000002 +115.10666666666667,-84.06666666666666,87.3,115.10666666666667,115.10666666666667,232.8 +115.15611111111112,-84.10277777777777,87.33749999999999,115.15611111111112,115.15611111111112,232.9 +115.20555555555555,-84.13888888888889,87.375,115.20555555555555,115.20555555555555,233.0 +115.255,-84.175,87.4125,115.255,115.255,233.10000000000002 +115.30444444444444,-84.21111111111111,87.45,115.30444444444444,115.30444444444444,233.20000000000002 +115.35388888888889,-84.24722222222222,87.4875,115.35388888888889,115.35388888888889,233.3 +115.40333333333334,-84.28333333333333,87.52499999999999,115.40333333333334,115.40333333333334,233.4 +115.45277777777778,-84.31944444444444,87.5625,115.45277777777778,115.45277777777778,233.5 +115.50222222222222,-84.35555555555555,87.6,115.50222222222222,115.50222222222222,233.60000000000002 +115.55166666666666,-84.39166666666667,87.6375,115.55166666666666,115.55166666666666,233.70000000000002 +115.60111111111111,-84.42777777777776,87.675,115.60111111111111,115.60111111111111,233.8 +115.65055555555556,-84.46388888888887,87.71249999999999,115.65055555555556,115.65055555555556,233.9 +115.7,-84.49999999999999,87.75,115.7,115.7,234.0 +115.74944444444444,-84.5361111111111,87.7875,115.74944444444444,115.74944444444444,234.10000000000002 +115.79888888888888,-84.57222222222221,87.825,115.79888888888888,115.79888888888888,234.20000000000002 +115.84833333333333,-84.60833333333332,87.8625,115.84833333333333,115.84833333333333,234.3 +115.89777777777778,-84.64444444444443,87.89999999999999,115.89777777777778,115.89777777777778,234.4 +115.94722222222222,-84.68055555555554,87.9375,115.94722222222222,115.94722222222222,234.5 +115.99666666666667,-84.71666666666665,87.975,115.99666666666667,115.99666666666667,234.60000000000002 +116.0461111111111,-84.75277777777777,88.0125,116.0461111111111,116.0461111111111,234.70000000000002 +116.09555555555555,-84.78888888888888,88.05,116.09555555555555,116.09555555555555,234.8 +116.145,-84.82499999999999,88.08749999999999,116.145,116.145,234.9 +116.19444444444444,-84.8611111111111,88.125,116.19444444444444,116.19444444444444,235.0 +116.24388888888889,-84.89722222222221,88.1625,116.24388888888889,116.24388888888889,235.10000000000002 +116.29333333333334,-84.93333333333332,88.2,116.29333333333334,116.29333333333334,235.20000000000002 +116.34277777777777,-84.96944444444443,88.2375,116.34277777777777,116.34277777777777,235.3 +116.39222222222222,-85.00555555555555,88.27499999999999,116.39222222222222,116.39222222222222,235.4 +116.44166666666666,-85.04166666666666,88.3125,116.44166666666666,116.44166666666666,235.5 +116.49111111111111,-85.07777777777777,88.35,116.49111111111111,116.49111111111111,235.60000000000002 +116.54055555555556,-85.11388888888888,88.3875,116.54055555555556,116.54055555555556,235.70000000000002 +116.59,-85.14999999999999,88.425,116.59,116.59,235.8 +116.63944444444444,-85.1861111111111,88.46249999999999,116.63944444444444,116.63944444444444,235.9 +116.68888888888888,-85.22222222222221,88.5,116.68888888888888,116.68888888888888,236.0 +116.73833333333333,-85.25833333333333,88.5375,116.73833333333333,116.73833333333333,236.10000000000002 +116.78777777777778,-85.29444444444444,88.575,116.78777777777778,116.78777777777778,236.20000000000002 +116.83722222222222,-85.33055555555555,88.6125,116.83722222222222,116.83722222222222,236.3 +116.88666666666667,-85.36666666666666,88.64999999999999,116.88666666666667,116.88666666666667,236.4 +116.9361111111111,-85.40277777777777,88.6875,116.9361111111111,116.9361111111111,236.5 +116.98555555555555,-85.43888888888888,88.725,116.98555555555555,116.98555555555555,236.60000000000002 +117.035,-85.475,88.7625,117.035,117.035,236.70000000000002 +117.08444444444444,-85.5111111111111,88.8,117.08444444444444,117.08444444444444,236.8 +117.13388888888889,-85.54722222222222,88.83749999999999,117.13388888888889,117.13388888888889,236.9 +117.18333333333334,-85.58333333333333,88.875,117.18333333333334,117.18333333333334,237.0 +117.23277777777777,-85.61944444444444,88.9125,117.23277777777777,117.23277777777777,237.10000000000002 +117.28222222222222,-85.65555555555555,88.95,117.28222222222222,117.28222222222222,237.20000000000002 +117.33166666666666,-85.69166666666666,88.9875,117.33166666666666,117.33166666666666,237.3 +117.38111111111111,-85.72777777777777,89.02499999999999,117.38111111111111,117.38111111111111,237.4 +117.43055555555556,-85.76388888888889,89.0625,117.43055555555556,117.43055555555556,237.5 +117.48,-85.8,89.1,117.48,117.48,237.60000000000002 +117.52944444444444,-85.83611111111111,89.1375,117.52944444444444,117.52944444444444,237.70000000000002 +117.57888888888888,-85.87222222222222,89.175,117.57888888888888,117.57888888888888,237.8 +117.62833333333333,-85.90833333333333,89.21249999999999,117.62833333333333,117.62833333333333,237.9 +117.67777777777778,-85.94444444444444,89.25,117.67777777777778,117.67777777777778,238.0 +117.72722222222222,-85.98055555555555,89.2875,117.72722222222222,117.72722222222222,238.10000000000002 +117.77666666666667,-86.01666666666665,89.325,117.77666666666667,117.77666666666667,238.20000000000002 +117.8261111111111,-86.05277777777776,89.3625,117.8261111111111,117.8261111111111,238.3 +117.87555555555555,-86.08888888888887,89.39999999999999,117.87555555555555,117.87555555555555,238.4 +117.925,-86.12499999999999,89.4375,117.925,117.925,238.5 +117.97444444444444,-86.1611111111111,89.475,117.97444444444444,117.97444444444444,238.60000000000002 +118.02388888888889,-86.19722222222221,89.5125,118.02388888888889,118.02388888888889,238.70000000000002 +118.07333333333334,-86.23333333333332,89.55,118.07333333333334,118.07333333333334,238.8 +118.12277777777777,-86.26944444444443,89.58749999999999,118.12277777777777,118.12277777777777,238.9 +118.17222222222222,-86.30555555555554,89.625,118.17222222222222,118.17222222222222,239.0 +118.22166666666666,-86.34166666666665,89.6625,118.22166666666666,118.22166666666666,239.10000000000002 +118.27111111111111,-86.37777777777777,89.7,118.27111111111111,118.27111111111111,239.20000000000002 +118.32055555555556,-86.41388888888888,89.7375,118.32055555555556,118.32055555555556,239.3 +118.37,-86.44999999999999,89.77499999999999,118.37,118.37,239.4 +118.41944444444444,-86.4861111111111,89.8125,118.41944444444444,118.41944444444444,239.5 +118.46888888888888,-86.52222222222221,89.85,118.46888888888888,118.46888888888888,239.60000000000002 +118.51833333333333,-86.55833333333332,89.8875,118.51833333333333,118.51833333333333,239.70000000000002 +118.56777777777778,-86.59444444444443,89.925,118.56777777777778,118.56777777777778,239.8 +118.61722222222222,-86.63055555555555,89.96249999999999,118.61722222222222,118.61722222222222,239.9 +118.66666666666667,-86.66666666666666,90.0,118.66666666666667,118.66666666666667,240.0 +118.7161111111111,-86.70277777777777,90.0375,118.7161111111111,118.7161111111111,240.10000000000002 +118.76555555555555,-86.73888888888888,90.075,118.76555555555555,118.76555555555555,240.20000000000002 +118.815,-86.77499999999999,90.1125,118.815,118.815,240.3 +118.86444444444444,-86.8111111111111,90.14999999999999,118.86444444444444,118.86444444444444,240.4 +118.91388888888889,-86.84722222222221,90.1875,118.91388888888889,118.91388888888889,240.5 +118.96333333333334,-86.88333333333333,90.225,118.96333333333334,118.96333333333334,240.60000000000002 +119.01277777777777,-86.91944444444444,90.2625,119.01277777777777,119.01277777777777,240.70000000000002 +119.06222222222222,-86.95555555555555,90.3,119.06222222222222,119.06222222222222,240.8 +119.11166666666666,-86.99166666666666,90.33749999999999,119.11166666666666,119.11166666666666,240.9 +119.16111111111111,-87.02777777777777,90.375,119.16111111111111,119.16111111111111,241.0 +119.21055555555556,-87.06388888888888,90.4125,119.21055555555556,119.21055555555556,241.10000000000002 +119.26,-87.1,90.45,119.26,119.26,241.20000000000002 +119.30944444444444,-87.1361111111111,90.4875,119.30944444444444,119.30944444444444,241.3 +119.35888888888888,-87.17222222222222,90.52499999999999,119.35888888888888,119.35888888888888,241.4 +119.40833333333333,-87.20833333333333,90.5625,119.40833333333333,119.40833333333333,241.5 +119.45777777777778,-87.24444444444444,90.6,119.45777777777778,119.45777777777778,241.60000000000002 +119.50722222222223,-87.28055555555555,90.6375,119.50722222222223,119.50722222222223,241.70000000000002 +119.55666666666666,-87.31666666666666,90.675,119.55666666666666,119.55666666666666,241.8 +119.6061111111111,-87.35277777777777,90.71249999999999,119.6061111111111,119.6061111111111,241.9 +119.65555555555555,-87.38888888888889,90.75,119.65555555555555,119.65555555555555,242.0 +119.705,-87.425,90.7875,119.705,119.705,242.10000000000002 +119.75444444444445,-87.46111111111111,90.825,119.75444444444445,119.75444444444445,242.20000000000002 +119.80388888888889,-87.49722222222222,90.8625,119.80388888888889,119.80388888888889,242.3 +119.85333333333332,-87.53333333333333,90.89999999999999,119.85333333333332,119.85333333333332,242.4 +119.90277777777777,-87.56944444444444,90.9375,119.90277777777777,119.90277777777777,242.5 +119.95222222222222,-87.60555555555555,90.975,119.95222222222222,119.95222222222222,242.60000000000002 +120.00166666666667,-87.64166666666665,91.0125,120.00166666666667,120.00166666666667,242.70000000000002 +120.05111111111111,-87.67777777777776,91.05,120.05111111111111,120.05111111111111,242.8 +120.10055555555556,-87.71388888888887,91.08749999999999,120.10055555555556,120.10055555555556,242.9 +120.14999999999999,-87.74999999999999,91.125,120.14999999999999,120.14999999999999,243.0 +120.19944444444444,-87.7861111111111,91.1625,120.19944444444444,120.19944444444444,243.10000000000002 +120.24888888888889,-87.82222222222221,91.2,120.24888888888889,120.24888888888889,243.20000000000002 +120.29833333333333,-87.85833333333332,91.2375,120.29833333333333,120.29833333333333,243.3 +120.34777777777778,-87.89444444444443,91.27499999999999,120.34777777777778,120.34777777777778,243.4 +120.39722222222223,-87.93055555555554,91.3125,120.39722222222223,120.39722222222223,243.5 +120.44666666666666,-87.96666666666665,91.35,120.44666666666666,120.44666666666666,243.60000000000002 +120.4961111111111,-88.00277777777777,91.3875,120.4961111111111,120.4961111111111,243.70000000000002 +120.54555555555555,-88.03888888888888,91.425,120.54555555555555,120.54555555555555,243.8 +120.595,-88.07499999999999,91.46249999999999,120.595,120.595,243.9 +120.64444444444445,-88.1111111111111,91.5,120.64444444444445,120.64444444444445,244.0 +120.69388888888889,-88.14722222222221,91.5375,120.69388888888889,120.69388888888889,244.10000000000002 +120.74333333333333,-88.18333333333332,91.575,120.74333333333333,120.74333333333333,244.20000000000002 +120.79277777777777,-88.21944444444443,91.6125,120.79277777777777,120.79277777777777,244.3 +120.84222222222222,-88.25555555555555,91.64999999999999,120.84222222222222,120.84222222222222,244.4 +120.89166666666667,-88.29166666666666,91.6875,120.89166666666667,120.89166666666667,244.5 +120.94111111111111,-88.32777777777777,91.725,120.94111111111111,120.94111111111111,244.60000000000002 +120.99055555555556,-88.36388888888888,91.7625,120.99055555555556,120.99055555555556,244.70000000000002 +121.03999999999999,-88.39999999999999,91.8,121.03999999999999,121.03999999999999,244.8 +121.08944444444444,-88.4361111111111,91.83749999999999,121.08944444444444,121.08944444444444,244.9 +121.13888888888889,-88.47222222222221,91.875,121.13888888888889,121.13888888888889,245.0 +121.18833333333333,-88.50833333333333,91.9125,121.18833333333333,121.18833333333333,245.10000000000002 +121.23777777777778,-88.54444444444444,91.95,121.23777777777778,121.23777777777778,245.20000000000002 +121.28722222222223,-88.58055555555555,91.9875,121.28722222222223,121.28722222222223,245.3 +121.33666666666666,-88.61666666666666,92.02499999999999,121.33666666666666,121.33666666666666,245.4 +121.3861111111111,-88.65277777777777,92.0625,121.3861111111111,121.3861111111111,245.5 +121.43555555555555,-88.68888888888888,92.1,121.43555555555555,121.43555555555555,245.60000000000002 +121.485,-88.725,92.1375,121.485,121.485,245.70000000000002 +121.53444444444445,-88.7611111111111,92.175,121.53444444444445,121.53444444444445,245.8 +121.5838888888889,-88.79722222222222,92.21249999999999,121.5838888888889,121.5838888888889,245.9 +121.63333333333333,-88.83333333333333,92.25,121.63333333333333,121.63333333333333,246.0 +121.68277777777777,-88.86944444444444,92.2875,121.68277777777777,121.68277777777777,246.10000000000002 +121.73222222222222,-88.90555555555555,92.325,121.73222222222222,121.73222222222222,246.20000000000002 +121.78166666666667,-88.94166666666666,92.3625,121.78166666666667,121.78166666666667,246.3 +121.83111111111111,-88.97777777777777,92.39999999999999,121.83111111111111,121.83111111111111,246.4 +121.88055555555556,-89.01388888888889,92.4375,121.88055555555556,121.88055555555556,246.5 +121.92999999999999,-89.05,92.475,121.92999999999999,121.92999999999999,246.60000000000002 +121.97944444444444,-89.08611111111111,92.5125,121.97944444444444,121.97944444444444,246.70000000000002 +122.02888888888889,-89.12222222222222,92.55,122.02888888888889,122.02888888888889,246.8 +122.07833333333333,-89.15833333333333,92.58749999999999,122.07833333333333,122.07833333333333,246.9 +122.12777777777778,-89.19444444444444,92.625,122.12777777777778,122.12777777777778,247.0 +122.17722222222223,-89.23055555555554,92.6625,122.17722222222223,122.17722222222223,247.10000000000002 +122.22666666666666,-89.26666666666665,92.7,122.22666666666666,122.22666666666666,247.20000000000002 +122.2761111111111,-89.30277777777776,92.7375,122.2761111111111,122.2761111111111,247.3 +122.32555555555555,-89.33888888888887,92.77499999999999,122.32555555555555,122.32555555555555,247.4 +122.375,-89.37499999999999,92.8125,122.375,122.375,247.5 +122.42444444444445,-89.4111111111111,92.85,122.42444444444445,122.42444444444445,247.60000000000002 +122.4738888888889,-89.44722222222221,92.8875,122.4738888888889,122.4738888888889,247.70000000000002 +122.52333333333333,-89.48333333333332,92.925,122.52333333333333,122.52333333333333,247.8 +122.57277777777777,-89.51944444444443,92.96249999999999,122.57277777777777,122.57277777777777,247.9 +122.62222222222222,-89.55555555555554,93.0,122.62222222222222,122.62222222222222,248.0 +122.67166666666667,-89.59166666666665,93.0375,122.67166666666667,122.67166666666667,248.10000000000002 +122.72111111111111,-89.62777777777777,93.075,122.72111111111111,122.72111111111111,248.20000000000002 +122.77055555555556,-89.66388888888888,93.1125,122.77055555555556,122.77055555555556,248.3 +122.82,-89.69999999999999,93.14999999999999,122.82,122.82,248.4 +122.86944444444444,-89.7361111111111,93.1875,122.86944444444444,122.86944444444444,248.5 +122.91888888888889,-89.77222222222221,93.225,122.91888888888889,122.91888888888889,248.60000000000002 +122.96833333333333,-89.80833333333332,93.2625,122.96833333333333,122.96833333333333,248.70000000000002 +123.01777777777778,-89.84444444444443,93.3,123.01777777777778,123.01777777777778,248.8 +123.06722222222221,-89.88055555555555,93.33749999999999,123.06722222222221,123.06722222222221,248.9 +123.11666666666666,-89.91666666666666,93.375,123.11666666666666,123.11666666666666,249.0 +123.1661111111111,-89.95277777777777,93.4125,123.1661111111111,123.1661111111111,249.10000000000002 +123.21555555555555,-89.98888888888888,93.45,123.21555555555555,123.21555555555555,249.20000000000002 +123.265,-90.02499999999999,93.4875,123.265,123.265,249.3 +123.31444444444445,-90.0611111111111,93.52499999999999,123.31444444444445,123.31444444444445,249.4 +123.36388888888888,-90.09722222222221,93.5625,123.36388888888888,123.36388888888888,249.5 +123.41333333333333,-90.13333333333333,93.6,123.41333333333333,123.41333333333333,249.60000000000002 +123.46277777777777,-90.16944444444444,93.6375,123.46277777777777,123.46277777777777,249.70000000000002 +123.51222222222222,-90.20555555555555,93.675,123.51222222222222,123.51222222222222,249.8 +123.56166666666667,-90.24166666666666,93.71249999999999,123.56166666666667,123.56166666666667,249.9 +123.61111111111111,-90.27777777777777,93.75,123.61111111111111,123.61111111111111,250.0 +123.66055555555555,-90.31388888888888,93.7875,123.66055555555555,123.66055555555555,250.10000000000002 +123.71,-90.35,93.825,123.71,123.71,250.20000000000002 +123.75944444444444,-90.3861111111111,93.8625,123.75944444444444,123.75944444444444,250.3 +123.80888888888889,-90.42222222222222,93.89999999999999,123.80888888888889,123.80888888888889,250.4 +123.85833333333333,-90.45833333333333,93.9375,123.85833333333333,123.85833333333333,250.5 +123.90777777777778,-90.49444444444444,93.975,123.90777777777778,123.90777777777778,250.60000000000002 +123.95722222222221,-90.53055555555555,94.0125,123.95722222222221,123.95722222222221,250.70000000000002 +124.00666666666666,-90.56666666666666,94.05,124.00666666666666,124.00666666666666,250.8 +124.05611111111111,-90.60277777777777,94.08749999999999,124.05611111111111,124.05611111111111,250.9 +124.10555555555555,-90.63888888888889,94.125,124.10555555555555,124.10555555555555,251.0 +124.155,-90.675,94.1625,124.155,124.155,251.10000000000002 +124.20444444444445,-90.71111111111111,94.2,124.20444444444445,124.20444444444445,251.20000000000002 +124.25388888888888,-90.74722222222222,94.2375,124.25388888888888,124.25388888888888,251.3 +124.30333333333333,-90.78333333333333,94.27499999999999,124.30333333333333,124.30333333333333,251.4 +124.35277777777777,-90.81944444444444,94.3125,124.35277777777777,124.35277777777777,251.5 +124.40222222222222,-90.85555555555554,94.35,124.40222222222222,124.40222222222222,251.60000000000002 +124.45166666666667,-90.89166666666665,94.3875,124.45166666666667,124.45166666666667,251.70000000000002 +124.50111111111111,-90.92777777777776,94.425,124.50111111111111,124.50111111111111,251.8 +124.55055555555555,-90.96388888888887,94.46249999999999,124.55055555555555,124.55055555555555,251.9 +124.6,-90.99999999999999,94.5,124.6,124.6,252.0 +124.64944444444444,-91.0361111111111,94.5375,124.64944444444444,124.64944444444444,252.10000000000002 +124.69888888888889,-91.07222222222221,94.575,124.69888888888889,124.69888888888889,252.20000000000002 +124.74833333333333,-91.10833333333332,94.6125,124.74833333333333,124.74833333333333,252.3 +124.79777777777778,-91.14444444444443,94.64999999999999,124.79777777777778,124.79777777777778,252.4 +124.84722222222221,-91.18055555555554,94.6875,124.84722222222221,124.84722222222221,252.5 +124.89666666666666,-91.21666666666665,94.725,124.89666666666666,124.89666666666666,252.60000000000002 +124.94611111111111,-91.25277777777777,94.7625,124.94611111111111,124.94611111111111,252.70000000000002 +124.99555555555555,-91.28888888888888,94.8,124.99555555555555,124.99555555555555,252.8 +125.045,-91.32499999999999,94.83749999999999,125.045,125.045,252.9 +125.09444444444445,-91.3611111111111,94.875,125.09444444444445,125.09444444444445,253.0 +125.14388888888888,-91.39722222222221,94.9125,125.14388888888888,125.14388888888888,253.10000000000002 +125.19333333333333,-91.43333333333332,94.95,125.19333333333333,125.19333333333333,253.20000000000002 +125.24277777777777,-91.46944444444443,94.9875,125.24277777777777,125.24277777777777,253.3 +125.29222222222222,-91.50555555555555,95.02499999999999,125.29222222222222,125.29222222222222,253.4 +125.34166666666667,-91.54166666666666,95.0625,125.34166666666667,125.34166666666667,253.5 +125.39111111111112,-91.57777777777777,95.1,125.39111111111112,125.39111111111112,253.60000000000002 +125.44055555555555,-91.61388888888888,95.1375,125.44055555555555,125.44055555555555,253.70000000000002 +125.49,-91.64999999999999,95.175,125.49,125.49,253.8 +125.53944444444444,-91.6861111111111,95.21249999999999,125.53944444444444,125.53944444444444,253.9 +125.58888888888889,-91.72222222222221,95.25,125.58888888888889,125.58888888888889,254.0 +125.63833333333334,-91.75833333333333,95.2875,125.63833333333334,125.63833333333334,254.10000000000002 +125.68777777777778,-91.79444444444444,95.325,125.68777777777778,125.68777777777778,254.20000000000002 +125.73722222222221,-91.83055555555555,95.3625,125.73722222222221,125.73722222222221,254.3 +125.78666666666666,-91.86666666666666,95.39999999999999,125.78666666666666,125.78666666666666,254.4 +125.83611111111111,-91.90277777777777,95.4375,125.83611111111111,125.83611111111111,254.5 +125.88555555555556,-91.93888888888888,95.475,125.88555555555556,125.88555555555556,254.60000000000002 +125.935,-91.975,95.5125,125.935,125.935,254.70000000000002 +125.98444444444445,-92.0111111111111,95.55,125.98444444444445,125.98444444444445,254.8 +126.03388888888888,-92.04722222222222,95.58749999999999,126.03388888888888,126.03388888888888,254.9 +126.08333333333333,-92.08333333333333,95.625,126.08333333333333,126.08333333333333,255.0 +126.13277777777778,-92.11944444444444,95.6625,126.13277777777778,126.13277777777778,255.10000000000002 +126.18222222222222,-92.15555555555555,95.7,126.18222222222222,126.18222222222222,255.20000000000002 +126.23166666666667,-92.19166666666666,95.7375,126.23166666666667,126.23166666666667,255.3 +126.28111111111112,-92.22777777777777,95.77499999999999,126.28111111111112,126.28111111111112,255.4 +126.33055555555555,-92.26388888888889,95.8125,126.33055555555555,126.33055555555555,255.5 +126.38,-92.3,95.85,126.38,126.38,255.60000000000002 +126.42944444444444,-92.33611111111111,95.8875,126.42944444444444,126.42944444444444,255.70000000000002 +126.47888888888889,-92.37222222222222,95.925,126.47888888888889,126.47888888888889,255.8 +126.52833333333334,-92.40833333333333,95.96249999999999,126.52833333333334,126.52833333333334,255.9 +126.57777777777778,-92.44444444444443,96.0,126.57777777777778,126.57777777777778,256.0 +126.62722222222222,-92.48055555555554,96.0375,126.62722222222222,126.62722222222222,256.1 +126.67666666666666,-92.51666666666665,96.075,126.67666666666666,126.67666666666666,256.2 +126.72611111111111,-92.55277777777776,96.1125,126.72611111111111,126.72611111111111,256.3 +126.77555555555556,-92.58888888888887,96.14999999999999,126.77555555555556,126.77555555555556,256.40000000000003 +126.825,-92.62499999999999,96.1875,126.825,126.825,256.5 +126.87444444444444,-92.6611111111111,96.225,126.87444444444444,126.87444444444444,256.6 +126.92388888888888,-92.69722222222221,96.2625,126.92388888888888,126.92388888888888,256.7 +126.97333333333333,-92.73333333333332,96.3,126.97333333333333,126.97333333333333,256.8 +127.02277777777778,-92.76944444444443,96.33749999999999,127.02277777777778,127.02277777777778,256.90000000000003 +127.07222222222222,-92.80555555555554,96.375,127.07222222222222,127.07222222222222,257.0 +127.12166666666667,-92.84166666666665,96.4125,127.12166666666667,127.12166666666667,257.1 +127.1711111111111,-92.87777777777777,96.45,127.1711111111111,127.1711111111111,257.2 +127.22055555555555,-92.91388888888888,96.4875,127.22055555555555,127.22055555555555,257.3 +127.27,-92.94999999999999,96.52499999999999,127.27,127.27,257.40000000000003 +127.31944444444444,-92.9861111111111,96.5625,127.31944444444444,127.31944444444444,257.5 +127.36888888888889,-93.02222222222221,96.6,127.36888888888889,127.36888888888889,257.6 +127.41833333333334,-93.05833333333332,96.6375,127.41833333333334,127.41833333333334,257.7 +127.46777777777777,-93.09444444444443,96.675,127.46777777777777,127.46777777777777,257.8 +127.51722222222222,-93.13055555555555,96.71249999999999,127.51722222222222,127.51722222222222,257.90000000000003 +127.56666666666666,-93.16666666666666,96.75,127.56666666666666,127.56666666666666,258.0 +127.61611111111111,-93.20277777777777,96.7875,127.61611111111111,127.61611111111111,258.1 +127.66555555555556,-93.23888888888888,96.825,127.66555555555556,127.66555555555556,258.2 +127.715,-93.27499999999999,96.8625,127.715,127.715,258.3 +127.76444444444444,-93.3111111111111,96.89999999999999,127.76444444444444,127.76444444444444,258.40000000000003 +127.81388888888888,-93.34722222222221,96.9375,127.81388888888888,127.81388888888888,258.5 +127.86333333333333,-93.38333333333333,96.975,127.86333333333333,127.86333333333333,258.6 +127.91277777777778,-93.41944444444444,97.0125,127.91277777777778,127.91277777777778,258.7 +127.96222222222222,-93.45555555555555,97.05,127.96222222222222,127.96222222222222,258.8 +128.01166666666666,-93.49166666666666,97.08749999999999,128.01166666666666,128.01166666666666,258.90000000000003 +128.0611111111111,-93.52777777777777,97.125,128.0611111111111,128.0611111111111,259.0 +128.11055555555555,-93.56388888888888,97.1625,128.11055555555555,128.11055555555555,259.1 +128.16,-93.6,97.2,128.16,128.16,259.2 +128.20944444444444,-93.6361111111111,97.2375,128.20944444444444,128.20944444444444,259.3 +128.2588888888889,-93.67222222222222,97.27499999999999,128.2588888888889,128.2588888888889,259.40000000000003 +128.30833333333334,-93.70833333333333,97.3125,128.30833333333334,128.30833333333334,259.5 +128.35777777777778,-93.74444444444444,97.35,128.35777777777778,128.35777777777778,259.6 +128.40722222222223,-93.78055555555555,97.3875,128.40722222222223,128.40722222222223,259.7 +128.45666666666668,-93.81666666666666,97.425,128.45666666666668,128.45666666666668,259.8 +128.5061111111111,-93.85277777777777,97.46249999999999,128.5061111111111,128.5061111111111,259.90000000000003 +128.55555555555554,-93.88888888888889,97.5,128.55555555555554,128.55555555555554,260.0 +128.605,-93.925,97.5375,128.605,128.605,260.1 +128.65444444444444,-93.96111111111111,97.575,128.65444444444444,128.65444444444444,260.2 +128.70388888888888,-93.99722222222222,97.6125,128.70388888888888,128.70388888888888,260.3 +128.75333333333333,-94.03333333333333,97.64999999999999,128.75333333333333,128.75333333333333,260.40000000000003 +128.80277777777778,-94.06944444444443,97.6875,128.80277777777778,128.80277777777778,260.5 +128.85222222222222,-94.10555555555554,97.725,128.85222222222222,128.85222222222222,260.6 +128.90166666666667,-94.14166666666665,97.7625,128.90166666666667,128.90166666666667,260.7 +128.95111111111112,-94.17777777777776,97.8,128.95111111111112,128.95111111111112,260.8 +129.00055555555556,-94.21388888888887,97.83749999999999,129.00055555555556,129.00055555555556,260.90000000000003 +129.05,-94.24999999999999,97.875,129.05,129.05,261.0 +129.09944444444443,-94.2861111111111,97.9125,129.09944444444443,129.09944444444443,261.1 +129.14888888888888,-94.32222222222221,97.95,129.14888888888888,129.14888888888888,261.2 +129.19833333333332,-94.35833333333332,97.9875,129.19833333333332,129.19833333333332,261.3 +129.24777777777777,-94.39444444444443,98.02499999999999,129.24777777777777,129.24777777777777,261.40000000000003 +129.29722222222222,-94.43055555555554,98.0625,129.29722222222222,129.29722222222222,261.5 +129.34666666666666,-94.46666666666665,98.1,129.34666666666666,129.34666666666666,261.6 +129.3961111111111,-94.50277777777777,98.1375,129.3961111111111,129.3961111111111,261.7 +129.44555555555556,-94.53888888888888,98.175,129.44555555555556,129.44555555555556,261.8 +129.495,-94.57499999999999,98.21249999999999,129.495,129.495,261.90000000000003 +129.54444444444445,-94.6111111111111,98.25,129.54444444444445,129.54444444444445,262.0 +129.5938888888889,-94.64722222222221,98.2875,129.5938888888889,129.5938888888889,262.1 +129.64333333333335,-94.68333333333332,98.325,129.64333333333335,129.64333333333335,262.2 +129.69277777777776,-94.71944444444443,98.3625,129.69277777777776,129.69277777777776,262.3 +129.7422222222222,-94.75555555555555,98.39999999999999,129.7422222222222,129.7422222222222,262.40000000000003 +129.79166666666666,-94.79166666666666,98.4375,129.79166666666666,129.79166666666666,262.5 +129.8411111111111,-94.82777777777777,98.475,129.8411111111111,129.8411111111111,262.6 +129.89055555555555,-94.86388888888888,98.5125,129.89055555555555,129.89055555555555,262.7 +129.94,-94.89999999999999,98.55,129.94,129.94,262.8 +129.98944444444444,-94.9361111111111,98.58749999999999,129.98944444444444,129.98944444444444,262.90000000000003 +130.0388888888889,-94.97222222222221,98.625,130.0388888888889,130.0388888888889,263.0 +130.08833333333334,-95.00833333333333,98.6625,130.08833333333334,130.08833333333334,263.1 +130.13777777777779,-95.04444444444444,98.7,130.13777777777779,130.13777777777779,263.2 +130.18722222222223,-95.08055555555555,98.7375,130.18722222222223,130.18722222222223,263.3 +130.23666666666665,-95.11666666666666,98.77499999999999,130.23666666666665,130.23666666666665,263.40000000000003 +130.2861111111111,-95.15277777777777,98.8125,130.2861111111111,130.2861111111111,263.5 +130.33555555555554,-95.18888888888888,98.85,130.33555555555554,130.33555555555554,263.6 +130.385,-95.225,98.8875,130.385,130.385,263.7 +130.43444444444444,-95.2611111111111,98.925,130.43444444444444,130.43444444444444,263.8 +130.48388888888888,-95.29722222222222,98.96249999999999,130.48388888888888,130.48388888888888,263.90000000000003 +130.53333333333333,-95.33333333333333,99.0,130.53333333333333,130.53333333333333,264.0 +130.58277777777778,-95.36944444444444,99.0375,130.58277777777778,130.58277777777778,264.1 +130.63222222222223,-95.40555555555555,99.075,130.63222222222223,130.63222222222223,264.2 +130.68166666666667,-95.44166666666666,99.1125,130.68166666666667,130.68166666666667,264.3 +130.73111111111112,-95.47777777777777,99.14999999999999,130.73111111111112,130.73111111111112,264.40000000000003 +130.78055555555557,-95.51388888888889,99.1875,130.78055555555557,130.78055555555557,264.5 +130.82999999999998,-95.55,99.225,130.82999999999998,130.82999999999998,264.6 +130.87944444444443,-95.58611111111111,99.2625,130.87944444444443,130.87944444444443,264.7 +130.92888888888888,-95.62222222222222,99.3,130.92888888888888,130.92888888888888,264.8 +130.97833333333332,-95.65833333333333,99.33749999999999,130.97833333333332,130.97833333333332,264.90000000000003 +131.02777777777777,-95.69444444444443,99.375,131.02777777777777,131.02777777777777,265.0 +131.07722222222222,-95.73055555555554,99.4125,131.07722222222222,131.07722222222222,265.1 +131.12666666666667,-95.76666666666665,99.45,131.12666666666667,131.12666666666667,265.2 +131.1761111111111,-95.80277777777776,99.4875,131.1761111111111,131.1761111111111,265.3 +131.22555555555556,-95.83888888888887,99.52499999999999,131.22555555555556,131.22555555555556,265.40000000000003 +131.275,-95.87499999999999,99.5625,131.275,131.275,265.5 +131.32444444444445,-95.9111111111111,99.6,131.32444444444445,131.32444444444445,265.6 +131.3738888888889,-95.94722222222221,99.6375,131.3738888888889,131.3738888888889,265.7 +131.42333333333332,-95.98333333333332,99.675,131.42333333333332,131.42333333333332,265.8 +131.47277777777776,-96.01944444444443,99.71249999999999,131.47277777777776,131.47277777777776,265.90000000000003 +131.5222222222222,-96.05555555555554,99.75,131.5222222222222,131.5222222222222,266.0 +131.57166666666666,-96.09166666666665,99.7875,131.57166666666666,131.57166666666666,266.1 +131.6211111111111,-96.12777777777777,99.825,131.6211111111111,131.6211111111111,266.2 +131.67055555555555,-96.16388888888888,99.8625,131.67055555555555,131.67055555555555,266.3 +131.72,-96.19999999999999,99.89999999999999,131.72,131.72,266.40000000000003 +131.76944444444445,-96.2361111111111,99.9375,131.76944444444445,131.76944444444445,266.5 +131.8188888888889,-96.27222222222221,99.975,131.8188888888889,131.8188888888889,266.6 +131.86833333333334,-96.30833333333332,100.0125,131.86833333333334,131.86833333333334,266.7 +131.9177777777778,-96.34444444444443,100.05,131.9177777777778,131.9177777777778,266.8 +131.96722222222223,-96.38055555555555,100.08749999999999,131.96722222222223,131.96722222222223,266.90000000000003 +132.01666666666665,-96.41666666666666,100.125,132.01666666666665,132.01666666666665,267.0 +132.0661111111111,-96.45277777777777,100.1625,132.0661111111111,132.0661111111111,267.1 +132.11555555555555,-96.48888888888888,100.2,132.11555555555555,132.11555555555555,267.2 +132.165,-96.52499999999999,100.2375,132.165,132.165,267.3 +132.21444444444444,-96.5611111111111,100.27499999999999,132.21444444444444,132.21444444444444,267.40000000000003 +132.26388888888889,-96.59722222222221,100.3125,132.26388888888889,132.26388888888889,267.5 +132.31333333333333,-96.63333333333333,100.35,132.31333333333333,132.31333333333333,267.6 +132.36277777777778,-96.66944444444444,100.3875,132.36277777777778,132.36277777777778,267.7 +132.41222222222223,-96.70555555555555,100.425,132.41222222222223,132.41222222222223,267.8 +132.46166666666667,-96.74166666666666,100.46249999999999,132.46166666666667,132.46166666666667,267.90000000000003 +132.51111111111112,-96.77777777777777,100.5,132.51111111111112,132.51111111111112,268.0 +132.56055555555557,-96.81388888888888,100.5375,132.56055555555557,132.56055555555557,268.1 +132.60999999999999,-96.85,100.575,132.60999999999999,132.60999999999999,268.2 +132.65944444444443,-96.8861111111111,100.6125,132.65944444444443,132.65944444444443,268.3 +132.70888888888888,-96.92222222222222,100.64999999999999,132.70888888888888,132.70888888888888,268.40000000000003 +132.75833333333333,-96.95833333333333,100.6875,132.75833333333333,132.75833333333333,268.5 +132.80777777777777,-96.99444444444444,100.725,132.80777777777777,132.80777777777777,268.6 +132.85722222222222,-97.03055555555555,100.7625,132.85722222222222,132.85722222222222,268.7 +132.90666666666667,-97.06666666666666,100.8,132.90666666666667,132.90666666666667,268.8 +132.9561111111111,-97.10277777777777,100.83749999999999,132.9561111111111,132.9561111111111,268.90000000000003 +133.00555555555556,-97.13888888888889,100.875,133.00555555555556,133.00555555555556,269.0 +133.055,-97.175,100.9125,133.055,133.055,269.1 +133.10444444444445,-97.21111111111111,100.95,133.10444444444445,133.10444444444445,269.2 +133.1538888888889,-97.24722222222222,100.9875,133.1538888888889,133.1538888888889,269.3 +133.20333333333332,-97.28333333333332,101.02499999999999,133.20333333333332,133.20333333333332,269.40000000000003 +133.25277777777777,-97.31944444444443,101.0625,133.25277777777777,133.25277777777777,269.5 +133.3022222222222,-97.35555555555554,101.1,133.3022222222222,133.3022222222222,269.6 +133.35166666666666,-97.39166666666665,101.1375,133.35166666666666,133.35166666666666,269.7 +133.4011111111111,-97.42777777777776,101.175,133.4011111111111,133.4011111111111,269.8 +133.45055555555555,-97.46388888888887,101.21249999999999,133.45055555555555,133.45055555555555,269.90000000000003 +133.5,-97.49999999999999,101.25,133.5,133.5,270.0 +133.54944444444445,-97.5361111111111,101.2875,133.54944444444445,133.54944444444445,270.1 +133.5988888888889,-97.57222222222221,101.325,133.5988888888889,133.5988888888889,270.2 +133.64833333333334,-97.60833333333332,101.3625,133.64833333333334,133.64833333333334,270.3 +133.6977777777778,-97.64444444444443,101.39999999999999,133.6977777777778,133.6977777777778,270.40000000000003 +133.74722222222223,-97.68055555555554,101.4375,133.74722222222223,133.74722222222223,270.5 +133.79666666666665,-97.71666666666665,101.475,133.79666666666665,133.79666666666665,270.6 +133.8461111111111,-97.75277777777777,101.5125,133.8461111111111,133.8461111111111,270.7 +133.89555555555555,-97.78888888888888,101.55,133.89555555555555,133.89555555555555,270.8 +133.945,-97.82499999999999,101.58749999999999,133.945,133.945,270.90000000000003 +133.99444444444444,-97.8611111111111,101.625,133.99444444444444,133.99444444444444,271.0 +134.0438888888889,-97.89722222222221,101.6625,134.0438888888889,134.0438888888889,271.1 +134.09333333333333,-97.93333333333332,101.7,134.09333333333333,134.09333333333333,271.2 +134.14277777777778,-97.96944444444443,101.7375,134.14277777777778,134.14277777777778,271.3 +134.19222222222223,-98.00555555555555,101.77499999999999,134.19222222222223,134.19222222222223,271.40000000000003 +134.24166666666667,-98.04166666666666,101.8125,134.24166666666667,134.24166666666667,271.5 +134.29111111111112,-98.07777777777777,101.85,134.29111111111112,134.29111111111112,271.6 +134.34055555555554,-98.11388888888888,101.8875,134.34055555555554,134.34055555555554,271.7 +134.39,-98.14999999999999,101.925,134.39,134.39,271.8 +134.43944444444443,-98.1861111111111,101.96249999999999,134.43944444444443,134.43944444444443,271.90000000000003 +134.48888888888888,-98.22222222222221,102.0,134.48888888888888,134.48888888888888,272.0 +134.53833333333333,-98.25833333333333,102.0375,134.53833333333333,134.53833333333333,272.1 +134.58777777777777,-98.29444444444444,102.075,134.58777777777777,134.58777777777777,272.2 +134.63722222222222,-98.33055555555555,102.1125,134.63722222222222,134.63722222222222,272.3 +134.68666666666667,-98.36666666666666,102.14999999999999,134.68666666666667,134.68666666666667,272.40000000000003 +134.73611111111111,-98.40277777777777,102.1875,134.73611111111111,134.73611111111111,272.5 +134.78555555555556,-98.43888888888888,102.225,134.78555555555556,134.78555555555556,272.6 +134.835,-98.475,102.2625,134.835,134.835,272.7 +134.88444444444445,-98.5111111111111,102.3,134.88444444444445,134.88444444444445,272.8 +134.93388888888887,-98.54722222222222,102.33749999999999,134.93388888888887,134.93388888888887,272.90000000000003 +134.98333333333332,-98.58333333333333,102.375,134.98333333333332,134.98333333333332,273.0 +135.03277777777777,-98.61944444444444,102.4125,135.03277777777777,135.03277777777777,273.1 +135.0822222222222,-98.65555555555555,102.45,135.0822222222222,135.0822222222222,273.2 +135.13166666666666,-98.69166666666666,102.4875,135.13166666666666,135.13166666666666,273.3 +135.1811111111111,-98.72777777777777,102.52499999999999,135.1811111111111,135.1811111111111,273.40000000000003 +135.23055555555555,-98.76388888888889,102.5625,135.23055555555555,135.23055555555555,273.5 +135.28,-98.8,102.6,135.28,135.28,273.6 +135.32944444444445,-98.83611111111111,102.6375,135.32944444444445,135.32944444444445,273.7 +135.3788888888889,-98.87222222222222,102.675,135.3788888888889,135.3788888888889,273.8 +135.42833333333334,-98.90833333333332,102.71249999999999,135.42833333333334,135.42833333333334,273.90000000000003 +135.4777777777778,-98.94444444444443,102.75,135.4777777777778,135.4777777777778,274.0 +135.5272222222222,-98.98055555555554,102.7875,135.5272222222222,135.5272222222222,274.1 +135.57666666666665,-99.01666666666665,102.825,135.57666666666665,135.57666666666665,274.2 +135.6261111111111,-99.05277777777776,102.8625,135.6261111111111,135.6261111111111,274.3 +135.67555555555555,-99.08888888888887,102.89999999999999,135.67555555555555,135.67555555555555,274.40000000000003 +135.725,-99.12499999999999,102.9375,135.725,135.725,274.5 +135.77444444444444,-99.1611111111111,102.975,135.77444444444444,135.77444444444444,274.6 +135.8238888888889,-99.19722222222221,103.0125,135.8238888888889,135.8238888888889,274.7 +135.87333333333333,-99.23333333333332,103.05,135.87333333333333,135.87333333333333,274.8 +135.92277777777778,-99.26944444444443,103.08749999999999,135.92277777777778,135.92277777777778,274.90000000000003 +135.97222222222223,-99.30555555555554,103.125,135.97222222222223,135.97222222222223,275.0 +136.02166666666668,-99.34166666666665,103.1625,136.02166666666668,136.02166666666668,275.1 +136.07111111111112,-99.37777777777777,103.2,136.07111111111112,136.07111111111112,275.2 +136.12055555555554,-99.41388888888888,103.2375,136.12055555555554,136.12055555555554,275.3 +136.17,-99.44999999999999,103.27499999999999,136.17,136.17,275.40000000000003 +136.21944444444443,-99.4861111111111,103.3125,136.21944444444443,136.21944444444443,275.5 +136.26888888888888,-99.52222222222221,103.35,136.26888888888888,136.26888888888888,275.6 +136.31833333333333,-99.55833333333332,103.3875,136.31833333333333,136.31833333333333,275.7 +136.36777777777777,-99.59444444444443,103.425,136.36777777777777,136.36777777777777,275.8 +136.41722222222222,-99.63055555555555,103.46249999999999,136.41722222222222,136.41722222222222,275.90000000000003 +136.46666666666667,-99.66666666666666,103.5,136.46666666666667,136.46666666666667,276.0 +136.51611111111112,-99.70277777777777,103.5375,136.51611111111112,136.51611111111112,276.1 +136.56555555555556,-99.73888888888888,103.575,136.56555555555556,136.56555555555556,276.2 +136.615,-99.77499999999999,103.6125,136.615,136.615,276.3 +136.66444444444446,-99.8111111111111,103.64999999999999,136.66444444444446,136.66444444444446,276.40000000000003 +136.71388888888887,-99.84722222222221,103.6875,136.71388888888887,136.71388888888887,276.5 +136.76333333333332,-99.88333333333333,103.725,136.76333333333332,136.76333333333332,276.6 +136.81277777777777,-99.91944444444444,103.7625,136.81277777777777,136.81277777777777,276.7 +136.86222222222221,-99.95555555555555,103.8,136.86222222222221,136.86222222222221,276.8 +136.91166666666666,-99.99166666666666,103.83749999999999,136.91166666666666,136.91166666666666,276.90000000000003 +136.9611111111111,-100.02777777777777,103.875,136.9611111111111,136.9611111111111,277.0 +137.01055555555556,-100.06388888888888,103.9125,137.01055555555556,137.01055555555556,277.1 +137.06,-100.1,103.95,137.06,137.06,277.2 +137.10944444444445,-100.1361111111111,103.9875,137.10944444444445,137.10944444444445,277.3 +137.1588888888889,-100.17222222222222,104.02499999999999,137.1588888888889,137.1588888888889,277.40000000000003 +137.20833333333334,-100.20833333333333,104.0625,137.20833333333334,137.20833333333334,277.5 +137.2577777777778,-100.24444444444444,104.1,137.2577777777778,137.2577777777778,277.6 +137.3072222222222,-100.28055555555555,104.1375,137.3072222222222,137.3072222222222,277.7 +137.35666666666665,-100.31666666666666,104.175,137.35666666666665,137.35666666666665,277.8 +137.4061111111111,-100.35277777777777,104.21249999999999,137.4061111111111,137.4061111111111,277.90000000000003 +137.45555555555555,-100.38888888888889,104.25,137.45555555555555,137.45555555555555,278.0 +137.505,-100.425,104.2875,137.505,137.505,278.1 +137.55444444444444,-100.46111111111111,104.325,137.55444444444444,137.55444444444444,278.2 +137.6038888888889,-100.4972222222222,104.3625,137.6038888888889,137.6038888888889,278.3 +137.65333333333334,-100.53333333333332,104.39999999999999,137.65333333333334,137.65333333333334,278.40000000000003 +137.70277777777778,-100.56944444444443,104.4375,137.70277777777778,137.70277777777778,278.5 +137.75222222222223,-100.60555555555554,104.475,137.75222222222223,137.75222222222223,278.6 +137.80166666666668,-100.64166666666665,104.5125,137.80166666666668,137.80166666666668,278.7 +137.8511111111111,-100.67777777777776,104.55,137.8511111111111,137.8511111111111,278.8 +137.90055555555554,-100.71388888888887,104.58749999999999,137.90055555555554,137.90055555555554,278.90000000000003 +137.95,-100.74999999999999,104.625,137.95,137.95,279.0 +137.99944444444444,-100.7861111111111,104.6625,137.99944444444444,137.99944444444444,279.1 +138.04888888888888,-100.82222222222221,104.7,138.04888888888888,138.04888888888888,279.2 +138.09833333333333,-100.85833333333332,104.7375,138.09833333333333,138.09833333333333,279.3 +138.14777777777778,-100.89444444444443,104.77499999999999,138.14777777777778,138.14777777777778,279.40000000000003 +138.19722222222222,-100.93055555555554,104.8125,138.19722222222222,138.19722222222222,279.5 +138.24666666666667,-100.96666666666665,104.85,138.24666666666667,138.24666666666667,279.6 +138.29611111111112,-101.00277777777777,104.8875,138.29611111111112,138.29611111111112,279.7 +138.34555555555556,-101.03888888888888,104.925,138.34555555555556,138.34555555555556,279.8 +138.395,-101.07499999999999,104.96249999999999,138.395,138.395,279.90000000000003 +138.44444444444443,-101.1111111111111,105.0,138.44444444444443,138.44444444444443,280.0 +138.49388888888888,-101.14722222222221,105.0375,138.49388888888888,138.49388888888888,280.1 +138.54333333333332,-101.18333333333332,105.075,138.54333333333332,138.54333333333332,280.2 +138.59277777777777,-101.21944444444443,105.1125,138.59277777777777,138.59277777777777,280.3 +138.64222222222222,-101.25555555555555,105.14999999999999,138.64222222222222,138.64222222222222,280.40000000000003 +138.69166666666666,-101.29166666666666,105.1875,138.69166666666666,138.69166666666666,280.5 +138.7411111111111,-101.32777777777777,105.225,138.7411111111111,138.7411111111111,280.6 +138.79055555555556,-101.36388888888888,105.2625,138.79055555555556,138.79055555555556,280.7 +138.84,-101.39999999999999,105.3,138.84,138.84,280.8 +138.88944444444445,-101.4361111111111,105.33749999999999,138.88944444444445,138.88944444444445,280.90000000000003 +138.9388888888889,-101.47222222222221,105.375,138.9388888888889,138.9388888888889,281.0 +138.98833333333334,-101.50833333333333,105.4125,138.98833333333334,138.98833333333334,281.1 +139.03777777777776,-101.54444444444444,105.45,139.03777777777776,139.03777777777776,281.2 +139.0872222222222,-101.58055555555555,105.4875,139.0872222222222,139.0872222222222,281.3 +139.13666666666666,-101.61666666666666,105.52499999999999,139.13666666666666,139.13666666666666,281.40000000000003 +139.1861111111111,-101.65277777777777,105.5625,139.1861111111111,139.1861111111111,281.5 +139.23555555555555,-101.68888888888888,105.6,139.23555555555555,139.23555555555555,281.6 +139.285,-101.725,105.6375,139.285,139.285,281.7 +139.33444444444444,-101.7611111111111,105.675,139.33444444444444,139.33444444444444,281.8 +139.3838888888889,-101.79722222222222,105.71249999999999,139.3838888888889,139.3838888888889,281.90000000000003 +139.43333333333334,-101.83333333333333,105.75,139.43333333333334,139.43333333333334,282.0 +139.48277777777778,-101.86944444444444,105.7875,139.48277777777778,139.48277777777778,282.1 +139.53222222222223,-101.90555555555555,105.825,139.53222222222223,139.53222222222223,282.2 +139.58166666666668,-101.94166666666666,105.8625,139.58166666666668,139.58166666666668,282.3 +139.6311111111111,-101.97777777777777,105.89999999999999,139.6311111111111,139.6311111111111,282.40000000000003 +139.68055555555554,-102.01388888888889,105.9375,139.68055555555554,139.68055555555554,282.5 +139.73,-102.05,105.975,139.73,139.73,282.6 +139.77944444444444,-102.08611111111111,106.0125,139.77944444444444,139.77944444444444,282.7 +139.82888888888888,-102.1222222222222,106.05,139.82888888888888,139.82888888888888,282.8 +139.87833333333333,-102.15833333333332,106.08749999999999,139.87833333333333,139.87833333333333,282.90000000000003 +139.92777777777778,-102.19444444444443,106.125,139.92777777777778,139.92777777777778,283.0 +139.97722222222222,-102.23055555555554,106.1625,139.97722222222222,139.97722222222222,283.1 +140.02666666666667,-102.26666666666665,106.2,140.02666666666667,140.02666666666667,283.2 +140.07611111111112,-102.30277777777776,106.2375,140.07611111111112,140.07611111111112,283.3 +140.12555555555556,-102.33888888888887,106.27499999999999,140.12555555555556,140.12555555555556,283.40000000000003 +140.175,-102.37499999999999,106.3125,140.175,140.175,283.5 +140.22444444444443,-102.4111111111111,106.35,140.22444444444443,140.22444444444443,283.6 +140.27388888888888,-102.44722222222221,106.3875,140.27388888888888,140.27388888888888,283.7 +140.32333333333332,-102.48333333333332,106.425,140.32333333333332,140.32333333333332,283.8 +140.37277777777777,-102.51944444444443,106.46249999999999,140.37277777777777,140.37277777777777,283.90000000000003 +140.42222222222222,-102.55555555555554,106.5,140.42222222222222,140.42222222222222,284.0 +140.47166666666666,-102.59166666666665,106.5375,140.47166666666666,140.47166666666666,284.1 +140.5211111111111,-102.62777777777777,106.575,140.5211111111111,140.5211111111111,284.2 +140.57055555555556,-102.66388888888888,106.6125,140.57055555555556,140.57055555555556,284.3 +140.62,-102.69999999999999,106.64999999999999,140.62,140.62,284.40000000000003 +140.66944444444445,-102.7361111111111,106.6875,140.66944444444445,140.66944444444445,284.5 +140.7188888888889,-102.77222222222221,106.725,140.7188888888889,140.7188888888889,284.6 +140.76833333333335,-102.80833333333332,106.7625,140.76833333333335,140.76833333333335,284.7 +140.81777777777776,-102.84444444444443,106.8,140.81777777777776,140.81777777777776,284.8 +140.8672222222222,-102.88055555555555,106.83749999999999,140.8672222222222,140.8672222222222,284.90000000000003 +140.91666666666666,-102.91666666666666,106.875,140.91666666666666,140.91666666666666,285.0 +140.9661111111111,-102.95277777777777,106.9125,140.9661111111111,140.9661111111111,285.1 +141.01555555555555,-102.98888888888888,106.95,141.01555555555555,141.01555555555555,285.2 +141.065,-103.02499999999999,106.9875,141.065,141.065,285.3 +141.11444444444444,-103.0611111111111,107.02499999999999,141.11444444444444,141.11444444444444,285.40000000000003 +141.1638888888889,-103.09722222222221,107.0625,141.1638888888889,141.1638888888889,285.5 +141.21333333333334,-103.13333333333333,107.1,141.21333333333334,141.21333333333334,285.6 +141.26277777777779,-103.16944444444444,107.1375,141.26277777777779,141.26277777777779,285.7 +141.31222222222223,-103.20555555555555,107.175,141.31222222222223,141.31222222222223,285.8 +141.36166666666665,-103.24166666666666,107.21249999999999,141.36166666666665,141.36166666666665,285.90000000000003 +141.4111111111111,-103.27777777777777,107.25,141.4111111111111,141.4111111111111,286.0 +141.46055555555554,-103.31388888888888,107.2875,141.46055555555554,141.46055555555554,286.1 +141.51,-103.35,107.325,141.51,141.51,286.2 +141.55944444444444,-103.3861111111111,107.3625,141.55944444444444,141.55944444444444,286.3 +141.60888888888888,-103.42222222222222,107.39999999999999,141.60888888888888,141.60888888888888,286.40000000000003 +141.65833333333333,-103.45833333333333,107.4375,141.65833333333333,141.65833333333333,286.5 +141.70777777777778,-103.49444444444444,107.475,141.70777777777778,141.70777777777778,286.6 +141.75722222222223,-103.53055555555555,107.5125,141.75722222222223,141.75722222222223,286.7 +141.80666666666667,-103.56666666666666,107.55,141.80666666666667,141.80666666666667,286.8 +141.85611111111112,-103.60277777777777,107.58749999999999,141.85611111111112,141.85611111111112,286.90000000000003 +141.90555555555557,-103.63888888888889,107.625,141.90555555555557,141.90555555555557,287.0 +141.95499999999998,-103.675,107.6625,141.95499999999998,141.95499999999998,287.1 +142.00444444444443,-103.7111111111111,107.7,142.00444444444443,142.00444444444443,287.2 +142.05388888888888,-103.7472222222222,107.7375,142.05388888888888,142.05388888888888,287.3 +142.10333333333332,-103.78333333333332,107.77499999999999,142.10333333333332,142.10333333333332,287.40000000000003 +142.15277777777777,-103.81944444444443,107.8125,142.15277777777777,142.15277777777777,287.5 +142.20222222222222,-103.85555555555554,107.85,142.20222222222222,142.20222222222222,287.6 +142.25166666666667,-103.89166666666665,107.8875,142.25166666666667,142.25166666666667,287.7 +142.3011111111111,-103.92777777777776,107.925,142.3011111111111,142.3011111111111,287.8 +142.35055555555556,-103.96388888888887,107.96249999999999,142.35055555555556,142.35055555555556,287.90000000000003 +142.4,-103.99999999999999,108.0,142.4,142.4,288.0 +142.44944444444445,-104.0361111111111,108.0375,142.44944444444445,142.44944444444445,288.1 +142.4988888888889,-104.07222222222221,108.075,142.4988888888889,142.4988888888889,288.2 +142.54833333333332,-104.10833333333332,108.1125,142.54833333333332,142.54833333333332,288.3 +142.59777777777776,-104.14444444444443,108.14999999999999,142.59777777777776,142.59777777777776,288.40000000000003 +142.6472222222222,-104.18055555555554,108.1875,142.6472222222222,142.6472222222222,288.5 +142.69666666666666,-104.21666666666665,108.225,142.69666666666666,142.69666666666666,288.6 +142.7461111111111,-104.25277777777777,108.2625,142.7461111111111,142.7461111111111,288.7 +142.79555555555555,-104.28888888888888,108.3,142.79555555555555,142.79555555555555,288.8 +142.845,-104.32499999999999,108.33749999999999,142.845,142.845,288.90000000000003 +142.89444444444445,-104.3611111111111,108.375,142.89444444444445,142.89444444444445,289.0 +142.9438888888889,-104.39722222222221,108.4125,142.9438888888889,142.9438888888889,289.1 +142.99333333333334,-104.43333333333332,108.45,142.99333333333334,142.99333333333334,289.2 +143.0427777777778,-104.46944444444443,108.4875,143.0427777777778,143.0427777777778,289.3 +143.09222222222223,-104.50555555555555,108.52499999999999,143.09222222222223,143.09222222222223,289.40000000000003 +143.14166666666665,-104.54166666666666,108.5625,143.14166666666665,143.14166666666665,289.5 +143.1911111111111,-104.57777777777777,108.6,143.1911111111111,143.1911111111111,289.6 +143.24055555555555,-104.61388888888888,108.6375,143.24055555555555,143.24055555555555,289.7 +143.29,-104.64999999999999,108.675,143.29,143.29,289.8 +143.33944444444444,-104.6861111111111,108.71249999999999,143.33944444444444,143.33944444444444,289.90000000000003 +143.38888888888889,-104.72222222222221,108.75,143.38888888888889,143.38888888888889,290.0 +143.43833333333333,-104.75833333333333,108.7875,143.43833333333333,143.43833333333333,290.1 +143.48777777777778,-104.79444444444444,108.825,143.48777777777778,143.48777777777778,290.2 +143.53722222222223,-104.83055555555555,108.8625,143.53722222222223,143.53722222222223,290.3 +143.58666666666667,-104.86666666666666,108.89999999999999,143.58666666666667,143.58666666666667,290.40000000000003 +143.63611111111112,-104.90277777777777,108.9375,143.63611111111112,143.63611111111112,290.5 +143.68555555555557,-104.93888888888888,108.975,143.68555555555557,143.68555555555557,290.6 +143.73499999999999,-104.975,109.0125,143.73499999999999,143.73499999999999,290.7 +143.78444444444443,-105.0111111111111,109.05,143.78444444444443,143.78444444444443,290.8 +143.83388888888888,-105.04722222222222,109.08749999999999,143.83388888888888,143.83388888888888,290.90000000000003 +143.88333333333333,-105.08333333333333,109.125,143.88333333333333,143.88333333333333,291.0 +143.93277777777777,-105.11944444444444,109.1625,143.93277777777777,143.93277777777777,291.1 +143.98222222222222,-105.15555555555555,109.2,143.98222222222222,143.98222222222222,291.2 +144.03166666666667,-105.19166666666666,109.2375,144.03166666666667,144.03166666666667,291.3 +144.0811111111111,-105.22777777777777,109.27499999999999,144.0811111111111,144.0811111111111,291.40000000000003 +144.13055555555556,-105.26388888888889,109.3125,144.13055555555556,144.13055555555556,291.5 +144.18,-105.3,109.35,144.18,144.18,291.6 +144.22944444444445,-105.3361111111111,109.3875,144.22944444444445,144.22944444444445,291.7 +144.2788888888889,-105.3722222222222,109.425,144.2788888888889,144.2788888888889,291.8 +144.32833333333332,-105.40833333333332,109.46249999999999,144.32833333333332,144.32833333333332,291.90000000000003 +144.37777777777777,-105.44444444444443,109.5,144.37777777777777,144.37777777777777,292.0 +144.4272222222222,-105.48055555555554,109.5375,144.4272222222222,144.4272222222222,292.1 +144.47666666666666,-105.51666666666665,109.575,144.47666666666666,144.47666666666666,292.2 +144.5261111111111,-105.55277777777776,109.6125,144.5261111111111,144.5261111111111,292.3 +144.57555555555555,-105.58888888888887,109.64999999999999,144.57555555555555,144.57555555555555,292.40000000000003 +144.625,-105.62499999999999,109.6875,144.625,144.625,292.5 +144.67444444444445,-105.6611111111111,109.725,144.67444444444445,144.67444444444445,292.6 +144.7238888888889,-105.69722222222221,109.7625,144.7238888888889,144.7238888888889,292.7 +144.77333333333334,-105.73333333333332,109.8,144.77333333333334,144.77333333333334,292.8 +144.8227777777778,-105.76944444444443,109.83749999999999,144.8227777777778,144.8227777777778,292.90000000000003 +144.8722222222222,-105.80555555555554,109.875,144.8722222222222,144.8722222222222,293.0 +144.92166666666665,-105.84166666666665,109.9125,144.92166666666665,144.92166666666665,293.1 +144.9711111111111,-105.87777777777777,109.95,144.9711111111111,144.9711111111111,293.2 +145.02055555555555,-105.91388888888888,109.9875,145.02055555555555,145.02055555555555,293.3 +145.07,-105.94999999999999,110.02499999999999,145.07,145.07,293.40000000000003 +145.11944444444444,-105.9861111111111,110.0625,145.11944444444444,145.11944444444444,293.5 +145.1688888888889,-106.02222222222221,110.1,145.1688888888889,145.1688888888889,293.6 +145.21833333333333,-106.05833333333332,110.1375,145.21833333333333,145.21833333333333,293.7 +145.26777777777778,-106.09444444444443,110.175,145.26777777777778,145.26777777777778,293.8 +145.31722222222223,-106.13055555555555,110.21249999999999,145.31722222222223,145.31722222222223,293.90000000000003 +145.36666666666667,-106.16666666666666,110.25,145.36666666666667,145.36666666666667,294.0 +145.41611111111112,-106.20277777777777,110.2875,145.41611111111112,145.41611111111112,294.1 +145.46555555555554,-106.23888888888888,110.325,145.46555555555554,145.46555555555554,294.2 +145.515,-106.27499999999999,110.3625,145.515,145.515,294.3 +145.56444444444443,-106.3111111111111,110.39999999999999,145.56444444444443,145.56444444444443,294.40000000000003 +145.61388888888888,-106.34722222222221,110.4375,145.61388888888888,145.61388888888888,294.5 +145.66333333333333,-106.38333333333333,110.475,145.66333333333333,145.66333333333333,294.6 +145.71277777777777,-106.41944444444444,110.5125,145.71277777777777,145.71277777777777,294.7 +145.76222222222222,-106.45555555555555,110.55,145.76222222222222,145.76222222222222,294.8 +145.81166666666667,-106.49166666666666,110.58749999999999,145.81166666666667,145.81166666666667,294.90000000000003 +145.86111111111111,-106.52777777777777,110.625,145.86111111111111,145.86111111111111,295.0 +145.91055555555556,-106.56388888888888,110.6625,145.91055555555556,145.91055555555556,295.1 +145.96,-106.6,110.7,145.96,145.96,295.2 +146.00944444444445,-106.6361111111111,110.7375,146.00944444444445,146.00944444444445,295.3 +146.05888888888887,-106.67222222222222,110.77499999999999,146.05888888888887,146.05888888888887,295.40000000000003 +146.10833333333332,-106.70833333333333,110.8125,146.10833333333332,146.10833333333332,295.5 +146.15777777777777,-106.74444444444444,110.85,146.15777777777777,146.15777777777777,295.6 +146.2072222222222,-106.78055555555555,110.8875,146.2072222222222,146.2072222222222,295.7 +146.25666666666666,-106.81666666666666,110.925,146.25666666666666,146.25666666666666,295.8 +146.3061111111111,-106.85277777777777,110.96249999999999,146.3061111111111,146.3061111111111,295.90000000000003 +146.35555555555555,-106.88888888888889,111.0,146.35555555555555,146.35555555555555,296.0 +146.405,-106.92499999999998,111.0375,146.405,146.405,296.1 +146.45444444444445,-106.9611111111111,111.075,146.45444444444445,146.45444444444445,296.2 +146.5038888888889,-106.9972222222222,111.1125,146.5038888888889,146.5038888888889,296.3 +146.55333333333334,-107.03333333333332,111.14999999999999,146.55333333333334,146.55333333333334,296.40000000000003 +146.6027777777778,-107.06944444444443,111.1875,146.6027777777778,146.6027777777778,296.5 +146.6522222222222,-107.10555555555554,111.225,146.6522222222222,146.6522222222222,296.6 +146.70166666666665,-107.14166666666665,111.2625,146.70166666666665,146.70166666666665,296.7 +146.7511111111111,-107.17777777777776,111.3,146.7511111111111,146.7511111111111,296.8 +146.80055555555555,-107.21388888888887,111.33749999999999,146.80055555555555,146.80055555555555,296.90000000000003 +146.85,-107.24999999999999,111.375,146.85,146.85,297.0 +146.89944444444444,-107.2861111111111,111.4125,146.89944444444444,146.89944444444444,297.1 +146.9488888888889,-107.32222222222221,111.45,146.9488888888889,146.9488888888889,297.2 +146.99833333333333,-107.35833333333332,111.4875,146.99833333333333,146.99833333333333,297.3 +147.04777777777778,-107.39444444444443,111.52499999999999,147.04777777777778,147.04777777777778,297.40000000000003 +147.09722222222223,-107.43055555555554,111.5625,147.09722222222223,147.09722222222223,297.5 +147.14666666666668,-107.46666666666665,111.6,147.14666666666668,147.14666666666668,297.6 +147.19611111111112,-107.50277777777777,111.6375,147.19611111111112,147.19611111111112,297.7 +147.24555555555554,-107.53888888888888,111.675,147.24555555555554,147.24555555555554,297.8 +147.295,-107.57499999999999,111.71249999999999,147.295,147.295,297.90000000000003 +147.34444444444443,-107.6111111111111,111.75,147.34444444444443,147.34444444444443,298.0 +147.39388888888888,-107.64722222222221,111.7875,147.39388888888888,147.39388888888888,298.1 +147.44333333333333,-107.68333333333332,111.825,147.44333333333333,147.44333333333333,298.2 +147.49277777777777,-107.71944444444443,111.8625,147.49277777777777,147.49277777777777,298.3 +147.54222222222222,-107.75555555555555,111.89999999999999,147.54222222222222,147.54222222222222,298.40000000000003 +147.59166666666667,-107.79166666666666,111.9375,147.59166666666667,147.59166666666667,298.5 +147.64111111111112,-107.82777777777777,111.975,147.64111111111112,147.64111111111112,298.6 +147.69055555555556,-107.86388888888888,112.0125,147.69055555555556,147.69055555555556,298.7 +147.74,-107.89999999999999,112.05,147.74,147.74,298.8 +147.78944444444446,-107.9361111111111,112.08749999999999,147.78944444444446,147.78944444444446,298.90000000000003 +147.83888888888887,-107.97222222222221,112.125,147.83888888888887,147.83888888888887,299.0 +147.88833333333332,-108.00833333333333,112.1625,147.88833333333332,147.88833333333332,299.1 +147.93777777777777,-108.04444444444444,112.2,147.93777777777777,147.93777777777777,299.2 +147.98722222222221,-108.08055555555555,112.2375,147.98722222222221,147.98722222222221,299.3 +148.03666666666666,-108.11666666666666,112.27499999999999,148.03666666666666,148.03666666666666,299.40000000000003 +148.0861111111111,-108.15277777777777,112.3125,148.0861111111111,148.0861111111111,299.5 +148.13555555555556,-108.18888888888888,112.35,148.13555555555556,148.13555555555556,299.6 +148.185,-108.225,112.3875,148.185,148.185,299.7 +148.23444444444445,-108.2611111111111,112.425,148.23444444444445,148.23444444444445,299.8 +148.2838888888889,-108.29722222222222,112.46249999999999,148.2838888888889,148.2838888888889,299.90000000000003 +148.33333333333334,-108.33333333333333,112.5,148.33333333333334,148.33333333333334,300.0 +148.38277777777776,-108.36944444444444,112.5375,148.38277777777776,148.38277777777776,300.1 +148.4322222222222,-108.40555555555555,112.575,148.4322222222222,148.4322222222222,300.2 +148.48166666666665,-108.44166666666666,112.6125,148.48166666666665,148.48166666666665,300.3 +148.5311111111111,-108.47777777777777,112.64999999999999,148.5311111111111,148.5311111111111,300.40000000000003 +148.58055555555555,-108.51388888888889,112.6875,148.58055555555555,148.58055555555555,300.5 +148.63,-108.54999999999998,112.725,148.63,148.63,300.6 +148.67944444444444,-108.5861111111111,112.7625,148.67944444444444,148.67944444444444,300.7 +148.7288888888889,-108.6222222222222,112.8,148.7288888888889,148.7288888888889,300.8 +148.77833333333334,-108.65833333333332,112.83749999999999,148.77833333333334,148.77833333333334,300.90000000000003 +148.82777777777778,-108.69444444444443,112.875,148.82777777777778,148.82777777777778,301.0 +148.87722222222223,-108.73055555555554,112.9125,148.87722222222223,148.87722222222223,301.1 +148.92666666666668,-108.76666666666665,112.95,148.92666666666668,148.92666666666668,301.2 +148.9761111111111,-108.80277777777776,112.9875,148.9761111111111,148.9761111111111,301.3 +149.02555555555554,-108.83888888888887,113.02499999999999,149.02555555555554,149.02555555555554,301.40000000000003 +149.075,-108.87499999999999,113.0625,149.075,149.075,301.5 +149.12444444444444,-108.9111111111111,113.1,149.12444444444444,149.12444444444444,301.6 +149.17388888888888,-108.94722222222221,113.1375,149.17388888888888,149.17388888888888,301.7 +149.22333333333333,-108.98333333333332,113.175,149.22333333333333,149.22333333333333,301.8 +149.27277777777778,-109.01944444444443,113.21249999999999,149.27277777777778,149.27277777777778,301.90000000000003 +149.32222222222222,-109.05555555555554,113.25,149.32222222222222,149.32222222222222,302.0 +149.37166666666667,-109.09166666666665,113.2875,149.37166666666667,149.37166666666667,302.1 +149.42111111111112,-109.12777777777777,113.325,149.42111111111112,149.42111111111112,302.2 +149.47055555555556,-109.16388888888888,113.3625,149.47055555555556,149.47055555555556,302.3 +149.52,-109.19999999999999,113.39999999999999,149.52,149.52,302.40000000000003 +149.56944444444443,-109.2361111111111,113.4375,149.56944444444443,149.56944444444443,302.5 +149.61888888888888,-109.27222222222221,113.475,149.61888888888888,149.61888888888888,302.6 +149.66833333333332,-109.30833333333332,113.5125,149.66833333333332,149.66833333333332,302.7 +149.71777777777777,-109.34444444444443,113.55,149.71777777777777,149.71777777777777,302.8 +149.76722222222222,-109.38055555555555,113.58749999999999,149.76722222222222,149.76722222222222,302.90000000000003 +149.81666666666666,-109.41666666666666,113.625,149.81666666666666,149.81666666666666,303.0 +149.8661111111111,-109.45277777777777,113.6625,149.8661111111111,149.8661111111111,303.1 +149.91555555555556,-109.48888888888888,113.7,149.91555555555556,149.91555555555556,303.2 +149.965,-109.52499999999999,113.7375,149.965,149.965,303.3 +150.01444444444445,-109.5611111111111,113.77499999999999,150.01444444444445,150.01444444444445,303.40000000000003 +150.0638888888889,-109.59722222222221,113.8125,150.0638888888889,150.0638888888889,303.5 +150.11333333333334,-109.63333333333333,113.85,150.11333333333334,150.11333333333334,303.6 +150.16277777777776,-109.66944444444444,113.8875,150.16277777777776,150.16277777777776,303.7 +150.2122222222222,-109.70555555555555,113.925,150.2122222222222,150.2122222222222,303.8 +150.26166666666666,-109.74166666666666,113.96249999999999,150.26166666666666,150.26166666666666,303.90000000000003 +150.3111111111111,-109.77777777777777,114.0,150.3111111111111,150.3111111111111,304.0 +150.36055555555555,-109.81388888888888,114.0375,150.36055555555555,150.36055555555555,304.1 +150.41,-109.85,114.075,150.41,150.41,304.2 +150.45944444444444,-109.8861111111111,114.1125,150.45944444444444,150.45944444444444,304.3 +150.5088888888889,-109.92222222222222,114.14999999999999,150.5088888888889,150.5088888888889,304.40000000000003 +150.55833333333334,-109.95833333333333,114.1875,150.55833333333334,150.55833333333334,304.5 +150.60777777777778,-109.99444444444444,114.225,150.60777777777778,150.60777777777778,304.6 +150.65722222222223,-110.03055555555555,114.2625,150.65722222222223,150.65722222222223,304.7 +150.70666666666668,-110.06666666666666,114.3,150.70666666666668,150.70666666666668,304.8 +150.7561111111111,-110.10277777777777,114.33749999999999,150.7561111111111,150.7561111111111,304.90000000000003 +150.80555555555554,-110.13888888888887,114.375,150.80555555555554,150.80555555555554,305.0 +150.855,-110.17499999999998,114.4125,150.855,150.855,305.1 +150.90444444444444,-110.2111111111111,114.45,150.90444444444444,150.90444444444444,305.2 +150.95388888888888,-110.2472222222222,114.4875,150.95388888888888,150.95388888888888,305.3 +151.00333333333333,-110.28333333333332,114.52499999999999,151.00333333333333,151.00333333333333,305.40000000000003 +151.05277777777778,-110.31944444444443,114.5625,151.05277777777778,151.05277777777778,305.5 +151.10222222222222,-110.35555555555554,114.6,151.10222222222222,151.10222222222222,305.6 +151.15166666666667,-110.39166666666665,114.6375,151.15166666666667,151.15166666666667,305.7 +151.20111111111112,-110.42777777777776,114.675,151.20111111111112,151.20111111111112,305.8 +151.25055555555556,-110.46388888888887,114.71249999999999,151.25055555555556,151.25055555555556,305.90000000000003 +151.3,-110.49999999999999,114.75,151.3,151.3,306.0 +151.34944444444443,-110.5361111111111,114.7875,151.34944444444443,151.34944444444443,306.1 +151.39888888888888,-110.57222222222221,114.825,151.39888888888888,151.39888888888888,306.2 +151.44833333333332,-110.60833333333332,114.8625,151.44833333333332,151.44833333333332,306.3 +151.49777777777777,-110.64444444444443,114.89999999999999,151.49777777777777,151.49777777777777,306.40000000000003 +151.54722222222222,-110.68055555555554,114.9375,151.54722222222222,151.54722222222222,306.5 +151.59666666666666,-110.71666666666665,114.975,151.59666666666666,151.59666666666666,306.6 +151.6461111111111,-110.75277777777777,115.0125,151.6461111111111,151.6461111111111,306.7 +151.69555555555556,-110.78888888888888,115.05,151.69555555555556,151.69555555555556,306.8 +151.745,-110.82499999999999,115.08749999999999,151.745,151.745,306.90000000000003 +151.79444444444445,-110.8611111111111,115.125,151.79444444444445,151.79444444444445,307.0 +151.8438888888889,-110.89722222222221,115.1625,151.8438888888889,151.8438888888889,307.1 +151.89333333333332,-110.93333333333332,115.19999999999999,151.89333333333332,151.89333333333332,307.20000000000005 +151.94277777777776,-110.96944444444443,115.2375,151.94277777777776,151.94277777777776,307.3 +151.9922222222222,-111.00555555555555,115.27499999999999,151.9922222222222,151.9922222222222,307.40000000000003 +152.04166666666666,-111.04166666666666,115.3125,152.04166666666666,152.04166666666666,307.5 +152.0911111111111,-111.07777777777777,115.35,152.0911111111111,152.0911111111111,307.6 +152.14055555555555,-111.11388888888888,115.38749999999999,152.14055555555555,152.14055555555555,307.70000000000005 +152.19,-111.14999999999999,115.425,152.19,152.19,307.8 +152.23944444444444,-111.1861111111111,115.46249999999999,152.23944444444444,152.23944444444444,307.90000000000003 +152.2888888888889,-111.22222222222221,115.5,152.2888888888889,152.2888888888889,308.0 +152.33833333333334,-111.25833333333333,115.5375,152.33833333333334,152.33833333333334,308.1 +152.38777777777779,-111.29444444444444,115.57499999999999,152.38777777777779,152.38777777777779,308.20000000000005 +152.43722222222223,-111.33055555555555,115.6125,152.43722222222223,152.43722222222223,308.3 +152.48666666666665,-111.36666666666666,115.64999999999999,152.48666666666665,152.48666666666665,308.40000000000003 +152.5361111111111,-111.40277777777777,115.6875,152.5361111111111,152.5361111111111,308.5 +152.58555555555554,-111.43888888888888,115.725,152.58555555555554,152.58555555555554,308.6 +152.635,-111.475,115.76249999999999,152.635,152.635,308.70000000000005 +152.68444444444444,-111.5111111111111,115.8,152.68444444444444,152.68444444444444,308.8 +152.73388888888888,-111.54722222222222,115.83749999999999,152.73388888888888,152.73388888888888,308.90000000000003 +152.78333333333333,-111.58333333333333,115.875,152.78333333333333,152.78333333333333,309.0 +152.83277777777778,-111.61944444444444,115.9125,152.83277777777778,152.83277777777778,309.1 +152.88222222222223,-111.65555555555555,115.94999999999999,152.88222222222223,152.88222222222223,309.20000000000005 +152.93166666666667,-111.69166666666666,115.9875,152.93166666666667,152.93166666666667,309.3 +152.98111111111112,-111.72777777777777,116.02499999999999,152.98111111111112,152.98111111111112,309.40000000000003 +153.03055555555557,-111.76388888888887,116.0625,153.03055555555557,153.03055555555557,309.5 +153.07999999999998,-111.79999999999998,116.1,153.07999999999998,153.07999999999998,309.6 +153.12944444444443,-111.8361111111111,116.13749999999999,153.12944444444443,153.12944444444443,309.70000000000005 +153.17888888888888,-111.8722222222222,116.175,153.17888888888888,153.17888888888888,309.8 +153.22833333333332,-111.90833333333332,116.21249999999999,153.22833333333332,153.22833333333332,309.90000000000003 +153.27777777777777,-111.94444444444443,116.25,153.27777777777777,153.27777777777777,310.0 +153.32722222222222,-111.98055555555554,116.2875,153.32722222222222,153.32722222222222,310.1 +153.37666666666667,-112.01666666666665,116.32499999999999,153.37666666666667,153.37666666666667,310.20000000000005 +153.4261111111111,-112.05277777777776,116.3625,153.4261111111111,153.4261111111111,310.3 +153.47555555555556,-112.08888888888887,116.39999999999999,153.47555555555556,153.47555555555556,310.40000000000003 +153.525,-112.12499999999999,116.4375,153.525,153.525,310.5 +153.57444444444445,-112.1611111111111,116.475,153.57444444444445,153.57444444444445,310.6 +153.6238888888889,-112.19722222222221,116.51249999999999,153.6238888888889,153.6238888888889,310.70000000000005 +153.67333333333332,-112.23333333333332,116.55,153.67333333333332,153.67333333333332,310.8 +153.72277777777776,-112.26944444444443,116.58749999999999,153.72277777777776,153.72277777777776,310.90000000000003 +153.7722222222222,-112.30555555555554,116.625,153.7722222222222,153.7722222222222,311.0 +153.82166666666666,-112.34166666666665,116.6625,153.82166666666666,153.82166666666666,311.1 +153.8711111111111,-112.37777777777777,116.69999999999999,153.8711111111111,153.8711111111111,311.20000000000005 +153.92055555555555,-112.41388888888888,116.7375,153.92055555555555,153.92055555555555,311.3 +153.97,-112.44999999999999,116.77499999999999,153.97,153.97,311.40000000000003 +154.01944444444445,-112.4861111111111,116.8125,154.01944444444445,154.01944444444445,311.5 +154.0688888888889,-112.52222222222221,116.85,154.0688888888889,154.0688888888889,311.6 +154.11833333333334,-112.55833333333332,116.88749999999999,154.11833333333334,154.11833333333334,311.70000000000005 +154.1677777777778,-112.59444444444443,116.925,154.1677777777778,154.1677777777778,311.8 +154.21722222222223,-112.63055555555555,116.96249999999999,154.21722222222223,154.21722222222223,311.90000000000003 +154.26666666666665,-112.66666666666666,117.0,154.26666666666665,154.26666666666665,312.0 +154.3161111111111,-112.70277777777777,117.0375,154.3161111111111,154.3161111111111,312.1 +154.36555555555555,-112.73888888888888,117.07499999999999,154.36555555555555,154.36555555555555,312.20000000000005 +154.415,-112.77499999999999,117.1125,154.415,154.415,312.3 +154.46444444444444,-112.8111111111111,117.14999999999999,154.46444444444444,154.46444444444444,312.40000000000003 +154.51388888888889,-112.84722222222221,117.1875,154.51388888888889,154.51388888888889,312.5 +154.56333333333333,-112.88333333333333,117.225,154.56333333333333,154.56333333333333,312.6 +154.61277777777778,-112.91944444444444,117.26249999999999,154.61277777777778,154.61277777777778,312.70000000000005 +154.66222222222223,-112.95555555555555,117.3,154.66222222222223,154.66222222222223,312.8 +154.71166666666667,-112.99166666666666,117.33749999999999,154.71166666666667,154.71166666666667,312.90000000000003 +154.76111111111112,-113.02777777777777,117.375,154.76111111111112,154.76111111111112,313.0 +154.81055555555557,-113.06388888888888,117.4125,154.81055555555557,154.81055555555557,313.1 +154.85999999999999,-113.1,117.44999999999999,154.85999999999999,154.85999999999999,313.20000000000005 +154.90944444444443,-113.1361111111111,117.4875,154.90944444444443,154.90944444444443,313.3 +154.95888888888888,-113.17222222222222,117.52499999999999,154.95888888888888,154.95888888888888,313.40000000000003 +155.00833333333333,-113.20833333333333,117.5625,155.00833333333333,155.00833333333333,313.5 +155.05777777777777,-113.24444444444444,117.6,155.05777777777777,155.05777777777777,313.6 +155.10722222222222,-113.28055555555555,117.63749999999999,155.10722222222222,155.10722222222222,313.70000000000005 +155.15666666666667,-113.31666666666666,117.675,155.15666666666667,155.15666666666667,313.8 +155.2061111111111,-113.35277777777776,117.71249999999999,155.2061111111111,155.2061111111111,313.90000000000003 +155.25555555555556,-113.38888888888887,117.75,155.25555555555556,155.25555555555556,314.0 +155.305,-113.42499999999998,117.7875,155.305,155.305,314.1 +155.35444444444445,-113.4611111111111,117.82499999999999,155.35444444444445,155.35444444444445,314.20000000000005 +155.4038888888889,-113.4972222222222,117.8625,155.4038888888889,155.4038888888889,314.3 +155.45333333333332,-113.53333333333332,117.89999999999999,155.45333333333332,155.45333333333332,314.40000000000003 +155.50277777777777,-113.56944444444443,117.9375,155.50277777777777,155.50277777777777,314.5 +155.5522222222222,-113.60555555555554,117.975,155.5522222222222,155.5522222222222,314.6 +155.60166666666666,-113.64166666666665,118.01249999999999,155.60166666666666,155.60166666666666,314.70000000000005 +155.6511111111111,-113.67777777777776,118.05,155.6511111111111,155.6511111111111,314.8 +155.70055555555555,-113.71388888888887,118.08749999999999,155.70055555555555,155.70055555555555,314.90000000000003 +155.75,-113.74999999999999,118.125,155.75,155.75,315.0 +155.79944444444445,-113.7861111111111,118.1625,155.79944444444445,155.79944444444445,315.1 +155.8488888888889,-113.82222222222221,118.19999999999999,155.8488888888889,155.8488888888889,315.20000000000005 +155.89833333333334,-113.85833333333332,118.2375,155.89833333333334,155.89833333333334,315.3 +155.9477777777778,-113.89444444444443,118.27499999999999,155.9477777777778,155.9477777777778,315.40000000000003 +155.9972222222222,-113.93055555555554,118.3125,155.9972222222222,155.9972222222222,315.5 +156.04666666666665,-113.96666666666665,118.35,156.04666666666665,156.04666666666665,315.6 +156.0961111111111,-114.00277777777777,118.38749999999999,156.0961111111111,156.0961111111111,315.70000000000005 +156.14555555555555,-114.03888888888888,118.425,156.14555555555555,156.14555555555555,315.8 +156.195,-114.07499999999999,118.46249999999999,156.195,156.195,315.90000000000003 +156.24444444444444,-114.1111111111111,118.5,156.24444444444444,156.24444444444444,316.0 +156.2938888888889,-114.14722222222221,118.5375,156.2938888888889,156.2938888888889,316.1 +156.34333333333333,-114.18333333333332,118.57499999999999,156.34333333333333,156.34333333333333,316.20000000000005 +156.39277777777778,-114.21944444444443,118.6125,156.39277777777778,156.39277777777778,316.3 +156.44222222222223,-114.25555555555555,118.64999999999999,156.44222222222223,156.44222222222223,316.40000000000003 +156.49166666666667,-114.29166666666666,118.6875,156.49166666666667,156.49166666666667,316.5 +156.54111111111112,-114.32777777777777,118.725,156.54111111111112,156.54111111111112,316.6 +156.59055555555554,-114.36388888888888,118.76249999999999,156.59055555555554,156.59055555555554,316.70000000000005 +156.64,-114.39999999999999,118.8,156.64,156.64,316.8 +156.68944444444443,-114.4361111111111,118.83749999999999,156.68944444444443,156.68944444444443,316.90000000000003 +156.73888888888888,-114.47222222222221,118.875,156.73888888888888,156.73888888888888,317.0 +156.78833333333333,-114.50833333333333,118.9125,156.78833333333333,156.78833333333333,317.1 +156.83777777777777,-114.54444444444444,118.94999999999999,156.83777777777777,156.83777777777777,317.20000000000005 +156.88722222222222,-114.58055555555555,118.9875,156.88722222222222,156.88722222222222,317.3 +156.93666666666667,-114.61666666666666,119.02499999999999,156.93666666666667,156.93666666666667,317.40000000000003 +156.98611111111111,-114.65277777777777,119.0625,156.98611111111111,156.98611111111111,317.5 +157.03555555555556,-114.68888888888888,119.1,157.03555555555556,157.03555555555556,317.6 +157.085,-114.725,119.13749999999999,157.085,157.085,317.70000000000005 +157.13444444444445,-114.7611111111111,119.175,157.13444444444445,157.13444444444445,317.8 +157.18388888888887,-114.79722222222222,119.21249999999999,157.18388888888887,157.18388888888887,317.90000000000003 +157.23333333333332,-114.83333333333333,119.25,157.23333333333332,157.23333333333332,318.0 +157.28277777777777,-114.86944444444444,119.2875,157.28277777777777,157.28277777777777,318.1 +157.3322222222222,-114.90555555555555,119.32499999999999,157.3322222222222,157.3322222222222,318.20000000000005 +157.38166666666666,-114.94166666666666,119.3625,157.38166666666666,157.38166666666666,318.3 +157.4311111111111,-114.97777777777776,119.39999999999999,157.4311111111111,157.4311111111111,318.40000000000003 +157.48055555555555,-115.01388888888887,119.4375,157.48055555555555,157.48055555555555,318.5 +157.53,-115.04999999999998,119.475,157.53,157.53,318.6 +157.57944444444445,-115.0861111111111,119.51249999999999,157.57944444444445,157.57944444444445,318.70000000000005 +157.6288888888889,-115.1222222222222,119.55,157.6288888888889,157.6288888888889,318.8 +157.67833333333334,-115.15833333333332,119.58749999999999,157.67833333333334,157.67833333333334,318.90000000000003 +157.7277777777778,-115.19444444444443,119.625,157.7277777777778,157.7277777777778,319.0 +157.7772222222222,-115.23055555555554,119.6625,157.7772222222222,157.7772222222222,319.1 +157.82666666666665,-115.26666666666665,119.69999999999999,157.82666666666665,157.82666666666665,319.20000000000005 +157.8761111111111,-115.30277777777776,119.7375,157.8761111111111,157.8761111111111,319.3 +157.92555555555555,-115.33888888888887,119.77499999999999,157.92555555555555,157.92555555555555,319.40000000000003 +157.975,-115.37499999999999,119.8125,157.975,157.975,319.5 +158.02444444444444,-115.4111111111111,119.85,158.02444444444444,158.02444444444444,319.6 +158.0738888888889,-115.44722222222221,119.88749999999999,158.0738888888889,158.0738888888889,319.70000000000005 +158.12333333333333,-115.48333333333332,119.925,158.12333333333333,158.12333333333333,319.8 +158.17277777777778,-115.51944444444443,119.96249999999999,158.17277777777778,158.17277777777778,319.90000000000003 +158.22222222222223,-115.55555555555554,120.0,158.22222222222223,158.22222222222223,320.0 +158.27166666666668,-115.59166666666665,120.0375,158.27166666666668,158.27166666666668,320.1 +158.32111111111112,-115.62777777777777,120.07499999999999,158.32111111111112,158.32111111111112,320.20000000000005 +158.37055555555554,-115.66388888888888,120.1125,158.37055555555554,158.37055555555554,320.3 +158.42,-115.69999999999999,120.14999999999999,158.42,158.42,320.40000000000003 +158.46944444444443,-115.7361111111111,120.1875,158.46944444444443,158.46944444444443,320.5 +158.51888888888888,-115.77222222222221,120.225,158.51888888888888,158.51888888888888,320.6 +158.56833333333333,-115.80833333333332,120.26249999999999,158.56833333333333,158.56833333333333,320.70000000000005 +158.61777777777777,-115.84444444444443,120.3,158.61777777777777,158.61777777777777,320.8 +158.66722222222222,-115.88055555555555,120.33749999999999,158.66722222222222,158.66722222222222,320.90000000000003 +158.71666666666667,-115.91666666666666,120.375,158.71666666666667,158.71666666666667,321.0 +158.76611111111112,-115.95277777777777,120.4125,158.76611111111112,158.76611111111112,321.1 +158.81555555555556,-115.98888888888888,120.44999999999999,158.81555555555556,158.81555555555556,321.20000000000005 +158.865,-116.02499999999999,120.4875,158.865,158.865,321.3 +158.91444444444446,-116.0611111111111,120.52499999999999,158.91444444444446,158.91444444444446,321.40000000000003 +158.96388888888887,-116.09722222222221,120.5625,158.96388888888887,158.96388888888887,321.5 +159.01333333333332,-116.13333333333333,120.6,159.01333333333332,159.01333333333332,321.6 +159.06277777777777,-116.16944444444444,120.63749999999999,159.06277777777777,159.06277777777777,321.70000000000005 +159.11222222222221,-116.20555555555555,120.675,159.11222222222221,159.11222222222221,321.8 +159.16166666666666,-116.24166666666666,120.71249999999999,159.16166666666666,159.16166666666666,321.90000000000003 +159.2111111111111,-116.27777777777777,120.75,159.2111111111111,159.2111111111111,322.0 +159.26055555555556,-116.31388888888888,120.7875,159.26055555555556,159.26055555555556,322.1 +159.31,-116.35,120.82499999999999,159.31,159.31,322.20000000000005 +159.35944444444445,-116.3861111111111,120.8625,159.35944444444445,159.35944444444445,322.3 +159.4088888888889,-116.42222222222222,120.89999999999999,159.4088888888889,159.4088888888889,322.40000000000003 +159.45833333333334,-116.45833333333333,120.9375,159.45833333333334,159.45833333333334,322.5 +159.50777777777776,-116.49444444444444,120.975,159.50777777777776,159.50777777777776,322.6 +159.5572222222222,-116.53055555555555,121.01249999999999,159.5572222222222,159.5572222222222,322.70000000000005 +159.60666666666665,-116.56666666666665,121.05,159.60666666666665,159.60666666666665,322.8 +159.6561111111111,-116.60277777777776,121.08749999999999,159.6561111111111,159.6561111111111,322.90000000000003 +159.70555555555555,-116.63888888888887,121.125,159.70555555555555,159.70555555555555,323.0 +159.755,-116.67499999999998,121.1625,159.755,159.755,323.1 +159.80444444444444,-116.7111111111111,121.19999999999999,159.80444444444444,159.80444444444444,323.20000000000005 +159.8538888888889,-116.7472222222222,121.2375,159.8538888888889,159.8538888888889,323.3 +159.90333333333334,-116.78333333333332,121.27499999999999,159.90333333333334,159.90333333333334,323.40000000000003 +159.95277777777778,-116.81944444444443,121.3125,159.95277777777778,159.95277777777778,323.5 +160.00222222222223,-116.85555555555554,121.35,160.00222222222223,160.00222222222223,323.6 +160.05166666666668,-116.89166666666665,121.38749999999999,160.05166666666668,160.05166666666668,323.70000000000005 +160.1011111111111,-116.92777777777776,121.425,160.1011111111111,160.1011111111111,323.8 +160.15055555555554,-116.96388888888887,121.46249999999999,160.15055555555554,160.15055555555554,323.90000000000003 +160.2,-116.99999999999999,121.5,160.2,160.2,324.0 +160.24944444444444,-117.0361111111111,121.5375,160.24944444444444,160.24944444444444,324.1 +160.29888888888888,-117.07222222222221,121.57499999999999,160.29888888888888,160.29888888888888,324.20000000000005 +160.34833333333333,-117.10833333333332,121.6125,160.34833333333333,160.34833333333333,324.3 +160.39777777777778,-117.14444444444443,121.64999999999999,160.39777777777778,160.39777777777778,324.40000000000003 +160.44722222222222,-117.18055555555554,121.6875,160.44722222222222,160.44722222222222,324.5 +160.49666666666667,-117.21666666666665,121.725,160.49666666666667,160.49666666666667,324.6 +160.54611111111112,-117.25277777777777,121.76249999999999,160.54611111111112,160.54611111111112,324.70000000000005 +160.59555555555556,-117.28888888888888,121.8,160.59555555555556,160.59555555555556,324.8 +160.645,-117.32499999999999,121.83749999999999,160.645,160.645,324.90000000000003 +160.69444444444443,-117.3611111111111,121.875,160.69444444444443,160.69444444444443,325.0 +160.74388888888888,-117.39722222222221,121.9125,160.74388888888888,160.74388888888888,325.1 +160.79333333333332,-117.43333333333332,121.94999999999999,160.79333333333332,160.79333333333332,325.20000000000005 +160.84277777777777,-117.46944444444443,121.9875,160.84277777777777,160.84277777777777,325.3 +160.89222222222222,-117.50555555555555,122.02499999999999,160.89222222222222,160.89222222222222,325.40000000000003 +160.94166666666666,-117.54166666666666,122.0625,160.94166666666666,160.94166666666666,325.5 +160.9911111111111,-117.57777777777777,122.1,160.9911111111111,160.9911111111111,325.6 +161.04055555555556,-117.61388888888888,122.13749999999999,161.04055555555556,161.04055555555556,325.70000000000005 +161.09,-117.64999999999999,122.175,161.09,161.09,325.8 +161.13944444444445,-117.6861111111111,122.21249999999999,161.13944444444445,161.13944444444445,325.90000000000003 +161.1888888888889,-117.72222222222221,122.25,161.1888888888889,161.1888888888889,326.0 +161.23833333333334,-117.75833333333333,122.2875,161.23833333333334,161.23833333333334,326.1 +161.28777777777776,-117.79444444444444,122.32499999999999,161.28777777777776,161.28777777777776,326.20000000000005 +161.3372222222222,-117.83055555555555,122.3625,161.3372222222222,161.3372222222222,326.3 +161.38666666666666,-117.86666666666666,122.39999999999999,161.38666666666666,161.38666666666666,326.40000000000003 +161.4361111111111,-117.90277777777777,122.4375,161.4361111111111,161.4361111111111,326.5 +161.48555555555555,-117.93888888888888,122.475,161.48555555555555,161.48555555555555,326.6 +161.535,-117.975,122.51249999999999,161.535,161.535,326.70000000000005 +161.58444444444444,-118.0111111111111,122.55,161.58444444444444,161.58444444444444,326.8 +161.6338888888889,-118.04722222222222,122.58749999999999,161.6338888888889,161.6338888888889,326.90000000000003 +161.68333333333334,-118.08333333333333,122.625,161.68333333333334,161.68333333333334,327.0 +161.73277777777778,-118.11944444444444,122.6625,161.73277777777778,161.73277777777778,327.1 +161.78222222222223,-118.15555555555555,122.69999999999999,161.78222222222223,161.78222222222223,327.20000000000005 +161.83166666666668,-118.19166666666665,122.7375,161.83166666666668,161.83166666666668,327.3 +161.8811111111111,-118.22777777777776,122.77499999999999,161.8811111111111,161.8811111111111,327.40000000000003 +161.93055555555554,-118.26388888888887,122.8125,161.93055555555554,161.93055555555554,327.5 +161.98,-118.29999999999998,122.85,161.98,161.98,327.6 +162.02944444444444,-118.3361111111111,122.88749999999999,162.02944444444444,162.02944444444444,327.70000000000005 +162.07888888888888,-118.3722222222222,122.925,162.07888888888888,162.07888888888888,327.8 +162.12833333333333,-118.40833333333332,122.96249999999999,162.12833333333333,162.12833333333333,327.90000000000003 +162.17777777777778,-118.44444444444443,123.0,162.17777777777778,162.17777777777778,328.0 +162.22722222222222,-118.48055555555554,123.0375,162.22722222222222,162.22722222222222,328.1 +162.27666666666667,-118.51666666666665,123.07499999999999,162.27666666666667,162.27666666666667,328.20000000000005 +162.32611111111112,-118.55277777777776,123.1125,162.32611111111112,162.32611111111112,328.3 +162.37555555555556,-118.58888888888887,123.14999999999999,162.37555555555556,162.37555555555556,328.40000000000003 +162.425,-118.62499999999999,123.1875,162.425,162.425,328.5 +162.47444444444443,-118.6611111111111,123.225,162.47444444444443,162.47444444444443,328.6 +162.52388888888888,-118.69722222222221,123.26249999999999,162.52388888888888,162.52388888888888,328.70000000000005 +162.57333333333332,-118.73333333333332,123.3,162.57333333333332,162.57333333333332,328.8 +162.62277777777777,-118.76944444444443,123.33749999999999,162.62277777777777,162.62277777777777,328.90000000000003 +162.67222222222222,-118.80555555555554,123.375,162.67222222222222,162.67222222222222,329.0 +162.72166666666666,-118.84166666666665,123.4125,162.72166666666666,162.72166666666666,329.1 +162.7711111111111,-118.87777777777777,123.44999999999999,162.7711111111111,162.7711111111111,329.20000000000005 +162.82055555555556,-118.91388888888888,123.4875,162.82055555555556,162.82055555555556,329.3 +162.87,-118.94999999999999,123.52499999999999,162.87,162.87,329.40000000000003 +162.91944444444445,-118.9861111111111,123.5625,162.91944444444445,162.91944444444445,329.5 +162.9688888888889,-119.02222222222221,123.6,162.9688888888889,162.9688888888889,329.6 +163.01833333333332,-119.05833333333332,123.63749999999999,163.01833333333332,163.01833333333332,329.70000000000005 +163.06777777777776,-119.09444444444443,123.675,163.06777777777776,163.06777777777776,329.8 +163.1172222222222,-119.13055555555555,123.71249999999999,163.1172222222222,163.1172222222222,329.90000000000003 +163.16666666666666,-119.16666666666666,123.75,163.16666666666666,163.16666666666666,330.0 +163.2161111111111,-119.20277777777777,123.7875,163.2161111111111,163.2161111111111,330.1 +163.26555555555555,-119.23888888888888,123.82499999999999,163.26555555555555,163.26555555555555,330.20000000000005 +163.315,-119.27499999999999,123.8625,163.315,163.315,330.3 +163.36444444444444,-119.3111111111111,123.89999999999999,163.36444444444444,163.36444444444444,330.40000000000003 +163.4138888888889,-119.34722222222221,123.9375,163.4138888888889,163.4138888888889,330.5 +163.46333333333334,-119.38333333333333,123.975,163.46333333333334,163.46333333333334,330.6 +163.51277777777779,-119.41944444444444,124.01249999999999,163.51277777777779,163.51277777777779,330.70000000000005 +163.56222222222223,-119.45555555555555,124.05,163.56222222222223,163.56222222222223,330.8 +163.61166666666665,-119.49166666666666,124.08749999999999,163.61166666666665,163.61166666666665,330.90000000000003 +163.6611111111111,-119.52777777777777,124.125,163.6611111111111,163.6611111111111,331.0 +163.71055555555554,-119.56388888888888,124.1625,163.71055555555554,163.71055555555554,331.1 +163.76,-119.6,124.19999999999999,163.76,163.76,331.20000000000005 +163.80944444444444,-119.6361111111111,124.2375,163.80944444444444,163.80944444444444,331.3 +163.85888888888888,-119.67222222222222,124.27499999999999,163.85888888888888,163.85888888888888,331.40000000000003 +163.90833333333333,-119.70833333333333,124.3125,163.90833333333333,163.90833333333333,331.5 +163.95777777777778,-119.74444444444444,124.35,163.95777777777778,163.95777777777778,331.6 +164.00722222222223,-119.78055555555554,124.38749999999999,164.00722222222223,164.00722222222223,331.70000000000005 +164.05666666666667,-119.81666666666665,124.425,164.05666666666667,164.05666666666667,331.8 +164.10611111111112,-119.85277777777776,124.46249999999999,164.10611111111112,164.10611111111112,331.90000000000003 +164.15555555555557,-119.88888888888887,124.5,164.15555555555557,164.15555555555557,332.0 +164.20499999999998,-119.92499999999998,124.5375,164.20499999999998,164.20499999999998,332.1 +164.25444444444443,-119.9611111111111,124.57499999999999,164.25444444444443,164.25444444444443,332.20000000000005 +164.30388888888888,-119.9972222222222,124.6125,164.30388888888888,164.30388888888888,332.3 +164.35333333333332,-120.03333333333332,124.64999999999999,164.35333333333332,164.35333333333332,332.40000000000003 +164.40277777777777,-120.06944444444443,124.6875,164.40277777777777,164.40277777777777,332.5 +164.45222222222222,-120.10555555555554,124.725,164.45222222222222,164.45222222222222,332.6 +164.50166666666667,-120.14166666666665,124.76249999999999,164.50166666666667,164.50166666666667,332.70000000000005 +164.5511111111111,-120.17777777777776,124.8,164.5511111111111,164.5511111111111,332.8 +164.60055555555556,-120.21388888888887,124.83749999999999,164.60055555555556,164.60055555555556,332.90000000000003 +164.65,-120.24999999999999,124.875,164.65,164.65,333.0 +164.69944444444445,-120.2861111111111,124.9125,164.69944444444445,164.69944444444445,333.1 +164.7488888888889,-120.32222222222221,124.94999999999999,164.7488888888889,164.7488888888889,333.20000000000005 +164.79833333333332,-120.35833333333332,124.9875,164.79833333333332,164.79833333333332,333.3 +164.84777777777776,-120.39444444444443,125.02499999999999,164.84777777777776,164.84777777777776,333.40000000000003 +164.8972222222222,-120.43055555555554,125.0625,164.8972222222222,164.8972222222222,333.5 +164.94666666666666,-120.46666666666665,125.1,164.94666666666666,164.94666666666666,333.6 +164.9961111111111,-120.50277777777777,125.13749999999999,164.9961111111111,164.9961111111111,333.70000000000005 +165.04555555555555,-120.53888888888888,125.175,165.04555555555555,165.04555555555555,333.8 +165.095,-120.57499999999999,125.21249999999999,165.095,165.095,333.90000000000003 +165.14444444444445,-120.6111111111111,125.25,165.14444444444445,165.14444444444445,334.0 +165.1938888888889,-120.64722222222221,125.2875,165.1938888888889,165.1938888888889,334.1 +165.24333333333334,-120.68333333333332,125.32499999999999,165.24333333333334,165.24333333333334,334.20000000000005 +165.2927777777778,-120.71944444444443,125.3625,165.2927777777778,165.2927777777778,334.3 +165.34222222222223,-120.75555555555555,125.39999999999999,165.34222222222223,165.34222222222223,334.40000000000003 +165.39166666666665,-120.79166666666666,125.4375,165.39166666666665,165.39166666666665,334.5 +165.4411111111111,-120.82777777777777,125.475,165.4411111111111,165.4411111111111,334.6 +165.49055555555555,-120.86388888888888,125.51249999999999,165.49055555555555,165.49055555555555,334.70000000000005 +165.54,-120.89999999999999,125.55,165.54,165.54,334.8 +165.58944444444444,-120.9361111111111,125.58749999999999,165.58944444444444,165.58944444444444,334.90000000000003 +165.63888888888889,-120.97222222222221,125.625,165.63888888888889,165.63888888888889,335.0 +165.68833333333333,-121.00833333333333,125.6625,165.68833333333333,165.68833333333333,335.1 +165.73777777777778,-121.04444444444444,125.69999999999999,165.73777777777778,165.73777777777778,335.20000000000005 +165.78722222222223,-121.08055555555555,125.7375,165.78722222222223,165.78722222222223,335.3 +165.83666666666667,-121.11666666666666,125.77499999999999,165.83666666666667,165.83666666666667,335.40000000000003 +165.88611111111112,-121.15277777777777,125.8125,165.88611111111112,165.88611111111112,335.5 +165.93555555555557,-121.18888888888888,125.85,165.93555555555557,165.93555555555557,335.6 +165.98499999999999,-121.225,125.88749999999999,165.98499999999999,165.98499999999999,335.70000000000005 +166.03444444444443,-121.2611111111111,125.925,166.03444444444443,166.03444444444443,335.8 +166.08388888888888,-121.29722222222222,125.96249999999999,166.08388888888888,166.08388888888888,335.90000000000003 +166.13333333333333,-121.33333333333333,126.0,166.13333333333333,166.13333333333333,336.0 +166.18277777777777,-121.36944444444444,126.0375,166.18277777777777,166.18277777777777,336.1 +166.23222222222222,-121.40555555555554,126.07499999999999,166.23222222222222,166.23222222222222,336.20000000000005 +166.28166666666667,-121.44166666666665,126.1125,166.28166666666667,166.28166666666667,336.3 +166.3311111111111,-121.47777777777776,126.14999999999999,166.3311111111111,166.3311111111111,336.40000000000003 +166.38055555555556,-121.51388888888887,126.1875,166.38055555555556,166.38055555555556,336.5 +166.43,-121.54999999999998,126.225,166.43,166.43,336.6 +166.47944444444445,-121.5861111111111,126.26249999999999,166.47944444444445,166.47944444444445,336.70000000000005 +166.52888888888887,-121.6222222222222,126.3,166.52888888888887,166.52888888888887,336.8 +166.57833333333332,-121.65833333333332,126.33749999999999,166.57833333333332,166.57833333333332,336.90000000000003 +166.62777777777777,-121.69444444444443,126.375,166.62777777777777,166.62777777777777,337.0 +166.6772222222222,-121.73055555555554,126.4125,166.6772222222222,166.6772222222222,337.1 +166.72666666666666,-121.76666666666665,126.44999999999999,166.72666666666666,166.72666666666666,337.20000000000005 +166.7761111111111,-121.80277777777776,126.4875,166.7761111111111,166.7761111111111,337.3 +166.82555555555555,-121.83888888888887,126.52499999999999,166.82555555555555,166.82555555555555,337.40000000000003 +166.875,-121.87499999999999,126.5625,166.875,166.875,337.5 +166.92444444444445,-121.9111111111111,126.6,166.92444444444445,166.92444444444445,337.6 +166.9738888888889,-121.94722222222221,126.63749999999999,166.9738888888889,166.9738888888889,337.70000000000005 +167.02333333333334,-121.98333333333332,126.675,167.02333333333334,167.02333333333334,337.8 +167.0727777777778,-122.01944444444443,126.71249999999999,167.0727777777778,167.0727777777778,337.90000000000003 +167.1222222222222,-122.05555555555554,126.75,167.1222222222222,167.1222222222222,338.0 +167.17166666666665,-122.09166666666665,126.7875,167.17166666666665,167.17166666666665,338.1 +167.2211111111111,-122.12777777777777,126.82499999999999,167.2211111111111,167.2211111111111,338.20000000000005 +167.27055555555555,-122.16388888888888,126.8625,167.27055555555555,167.27055555555555,338.3 +167.32,-122.19999999999999,126.89999999999999,167.32,167.32,338.40000000000003 +167.36944444444444,-122.2361111111111,126.9375,167.36944444444444,167.36944444444444,338.5 +167.4188888888889,-122.27222222222221,126.975,167.4188888888889,167.4188888888889,338.6 +167.46833333333333,-122.30833333333332,127.01249999999999,167.46833333333333,167.46833333333333,338.70000000000005 +167.51777777777778,-122.34444444444443,127.05,167.51777777777778,167.51777777777778,338.8 +167.56722222222223,-122.38055555555555,127.08749999999999,167.56722222222223,167.56722222222223,338.90000000000003 +167.61666666666667,-122.41666666666666,127.125,167.61666666666667,167.61666666666667,339.0 +167.66611111111112,-122.45277777777777,127.1625,167.66611111111112,167.66611111111112,339.1 +167.71555555555554,-122.48888888888888,127.19999999999999,167.71555555555554,167.71555555555554,339.20000000000005 +167.765,-122.52499999999999,127.2375,167.765,167.765,339.3 +167.81444444444443,-122.5611111111111,127.27499999999999,167.81444444444443,167.81444444444443,339.40000000000003 +167.86388888888888,-122.59722222222221,127.3125,167.86388888888888,167.86388888888888,339.5 +167.91333333333333,-122.63333333333333,127.35,167.91333333333333,167.91333333333333,339.6 +167.96277777777777,-122.66944444444444,127.38749999999999,167.96277777777777,167.96277777777777,339.70000000000005 +168.01222222222222,-122.70555555555555,127.425,168.01222222222222,168.01222222222222,339.8 +168.06166666666667,-122.74166666666666,127.46249999999999,168.06166666666667,168.06166666666667,339.90000000000003 +168.11111111111111,-122.77777777777777,127.5,168.11111111111111,168.11111111111111,340.0 +168.16055555555556,-122.81388888888888,127.5375,168.16055555555556,168.16055555555556,340.1 +168.21,-122.85,127.57499999999999,168.21,168.21,340.20000000000005 +168.25944444444445,-122.8861111111111,127.6125,168.25944444444445,168.25944444444445,340.3 +168.30888888888887,-122.92222222222222,127.64999999999999,168.30888888888887,168.30888888888887,340.40000000000003 +168.35833333333332,-122.95833333333333,127.6875,168.35833333333332,168.35833333333332,340.5 +168.40777777777777,-122.99444444444443,127.725,168.40777777777777,168.40777777777777,340.6 +168.4572222222222,-123.03055555555554,127.76249999999999,168.4572222222222,168.4572222222222,340.70000000000005 +168.50666666666666,-123.06666666666665,127.8,168.50666666666666,168.50666666666666,340.8 +168.5561111111111,-123.10277777777776,127.83749999999999,168.5561111111111,168.5561111111111,340.90000000000003 +168.60555555555555,-123.13888888888887,127.875,168.60555555555555,168.60555555555555,341.0 +168.655,-123.17499999999998,127.9125,168.655,168.655,341.1 +168.70444444444445,-123.2111111111111,127.94999999999999,168.70444444444445,168.70444444444445,341.20000000000005 +168.7538888888889,-123.2472222222222,127.9875,168.7538888888889,168.7538888888889,341.3 +168.80333333333334,-123.28333333333332,128.025,168.80333333333334,168.80333333333334,341.40000000000003 +168.8527777777778,-123.31944444444443,128.0625,168.8527777777778,168.8527777777778,341.5 +168.9022222222222,-123.35555555555554,128.1,168.9022222222222,168.9022222222222,341.6 +168.95166666666665,-123.39166666666665,128.1375,168.95166666666665,168.95166666666665,341.70000000000005 +169.0011111111111,-123.42777777777776,128.17499999999998,169.0011111111111,169.0011111111111,341.8 +169.05055555555555,-123.46388888888887,128.2125,169.05055555555555,169.05055555555555,341.90000000000003 +169.1,-123.49999999999999,128.25,169.1,169.1,342.0 +169.14944444444444,-123.5361111111111,128.2875,169.14944444444444,169.14944444444444,342.1 +169.1988888888889,-123.57222222222221,128.325,169.1988888888889,169.1988888888889,342.20000000000005 +169.24833333333333,-123.60833333333332,128.36249999999998,169.24833333333333,169.24833333333333,342.3 +169.29777777777778,-123.64444444444443,128.4,169.29777777777778,169.29777777777778,342.40000000000003 +169.34722222222223,-123.68055555555554,128.4375,169.34722222222223,169.34722222222223,342.5 +169.39666666666668,-123.71666666666665,128.475,169.39666666666668,169.39666666666668,342.6 +169.44611111111112,-123.75277777777777,128.5125,169.44611111111112,169.44611111111112,342.70000000000005 +169.49555555555554,-123.78888888888888,128.54999999999998,169.49555555555554,169.49555555555554,342.8 +169.545,-123.82499999999999,128.5875,169.545,169.545,342.90000000000003 +169.59444444444443,-123.8611111111111,128.625,169.59444444444443,169.59444444444443,343.0 +169.64388888888888,-123.89722222222221,128.6625,169.64388888888888,169.64388888888888,343.1 +169.69333333333333,-123.93333333333332,128.7,169.69333333333333,169.69333333333333,343.20000000000005 +169.74277777777777,-123.96944444444443,128.73749999999998,169.74277777777777,169.74277777777777,343.3 +169.79222222222222,-124.00555555555555,128.775,169.79222222222222,169.79222222222222,343.40000000000003 +169.84166666666667,-124.04166666666666,128.8125,169.84166666666667,169.84166666666667,343.5 +169.89111111111112,-124.07777777777777,128.85,169.89111111111112,169.89111111111112,343.6 +169.94055555555556,-124.11388888888888,128.8875,169.94055555555556,169.94055555555556,343.70000000000005 +169.99,-124.14999999999999,128.92499999999998,169.99,169.99,343.8 +170.03944444444443,-124.1861111111111,128.9625,170.03944444444443,170.03944444444443,343.90000000000003 +170.08888888888887,-124.22222222222221,129.0,170.08888888888887,170.08888888888887,344.0 +170.13833333333332,-124.25833333333333,129.0375,170.13833333333332,170.13833333333332,344.1 +170.18777777777777,-124.29444444444444,129.075,170.18777777777777,170.18777777777777,344.20000000000005 +170.23722222222221,-124.33055555555555,129.11249999999998,170.23722222222221,170.23722222222221,344.3 +170.28666666666666,-124.36666666666666,129.15,170.28666666666666,170.28666666666666,344.40000000000003 +170.3361111111111,-124.40277777777777,129.1875,170.3361111111111,170.3361111111111,344.5 +170.38555555555556,-124.43888888888888,129.225,170.38555555555556,170.38555555555556,344.6 +170.435,-124.475,129.2625,170.435,170.435,344.70000000000005 +170.48444444444445,-124.5111111111111,129.29999999999998,170.48444444444445,170.48444444444445,344.8 +170.5338888888889,-124.54722222222222,129.3375,170.5338888888889,170.5338888888889,344.90000000000003 +170.58333333333334,-124.58333333333333,129.375,170.58333333333334,170.58333333333334,345.0 +170.63277777777776,-124.61944444444443,129.4125,170.63277777777776,170.63277777777776,345.1 +170.6822222222222,-124.65555555555554,129.45,170.6822222222222,170.6822222222222,345.20000000000005 +170.73166666666665,-124.69166666666665,129.48749999999998,170.73166666666665,170.73166666666665,345.3 +170.7811111111111,-124.72777777777776,129.525,170.7811111111111,170.7811111111111,345.40000000000003 +170.83055555555555,-124.76388888888887,129.5625,170.83055555555555,170.83055555555555,345.5 +170.88,-124.79999999999998,129.6,170.88,170.88,345.6 +170.92944444444444,-124.8361111111111,129.6375,170.92944444444444,170.92944444444444,345.70000000000005 +170.9788888888889,-124.8722222222222,129.67499999999998,170.9788888888889,170.9788888888889,345.8 +171.02833333333334,-124.90833333333332,129.7125,171.02833333333334,171.02833333333334,345.90000000000003 +171.07777777777778,-124.94444444444443,129.75,171.07777777777778,171.07777777777778,346.0 +171.12722222222223,-124.98055555555554,129.7875,171.12722222222223,171.12722222222223,346.1 +171.17666666666668,-125.01666666666665,129.825,171.17666666666668,171.17666666666668,346.20000000000005 +171.2261111111111,-125.05277777777776,129.86249999999998,171.2261111111111,171.2261111111111,346.3 +171.27555555555554,-125.08888888888887,129.9,171.27555555555554,171.27555555555554,346.40000000000003 +171.325,-125.12499999999999,129.9375,171.325,171.325,346.5 +171.37444444444444,-125.1611111111111,129.975,171.37444444444444,171.37444444444444,346.6 +171.42388888888888,-125.19722222222221,130.0125,171.42388888888888,171.42388888888888,346.70000000000005 +171.47333333333333,-125.23333333333332,130.04999999999998,171.47333333333333,171.47333333333333,346.8 +171.52277777777778,-125.26944444444443,130.0875,171.52277777777778,171.52277777777778,346.90000000000003 +171.57222222222222,-125.30555555555554,130.125,171.57222222222222,171.57222222222222,347.0 +171.62166666666667,-125.34166666666665,130.1625,171.62166666666667,171.62166666666667,347.1 +171.67111111111112,-125.37777777777777,130.2,171.67111111111112,171.67111111111112,347.20000000000005 +171.72055555555556,-125.41388888888888,130.23749999999998,171.72055555555556,171.72055555555556,347.3 +171.77,-125.44999999999999,130.275,171.77,171.77,347.40000000000003 +171.81944444444443,-125.4861111111111,130.3125,171.81944444444443,171.81944444444443,347.5 +171.86888888888888,-125.52222222222221,130.35,171.86888888888888,171.86888888888888,347.6 +171.91833333333332,-125.55833333333332,130.3875,171.91833333333332,171.91833333333332,347.70000000000005 +171.96777777777777,-125.59444444444443,130.42499999999998,171.96777777777777,171.96777777777777,347.8 +172.01722222222222,-125.63055555555555,130.4625,172.01722222222222,172.01722222222222,347.90000000000003 +172.06666666666666,-125.66666666666666,130.5,172.06666666666666,172.06666666666666,348.0 +172.1161111111111,-125.70277777777777,130.5375,172.1161111111111,172.1161111111111,348.1 +172.16555555555556,-125.73888888888888,130.575,172.16555555555556,172.16555555555556,348.20000000000005 +172.215,-125.77499999999999,130.61249999999998,172.215,172.215,348.3 +172.26444444444445,-125.8111111111111,130.65,172.26444444444445,172.26444444444445,348.40000000000003 +172.3138888888889,-125.84722222222221,130.6875,172.3138888888889,172.3138888888889,348.5 +172.36333333333334,-125.88333333333333,130.725,172.36333333333334,172.36333333333334,348.6 +172.41277777777776,-125.91944444444444,130.7625,172.41277777777776,172.41277777777776,348.70000000000005 +172.4622222222222,-125.95555555555555,130.79999999999998,172.4622222222222,172.4622222222222,348.8 +172.51166666666666,-125.99166666666666,130.8375,172.51166666666666,172.51166666666666,348.90000000000003 +172.5611111111111,-126.02777777777777,130.875,172.5611111111111,172.5611111111111,349.0 +172.61055555555555,-126.06388888888888,130.9125,172.61055555555555,172.61055555555555,349.1 +172.66,-126.1,130.95,172.66,172.66,349.20000000000005 +172.70944444444444,-126.1361111111111,130.98749999999998,172.70944444444444,172.70944444444444,349.3 +172.7588888888889,-126.17222222222222,131.025,172.7588888888889,172.7588888888889,349.40000000000003 +172.80833333333334,-126.20833333333331,131.0625,172.80833333333334,172.80833333333334,349.5 +172.85777777777778,-126.24444444444443,131.1,172.85777777777778,172.85777777777778,349.6 +172.90722222222223,-126.28055555555554,131.1375,172.90722222222223,172.90722222222223,349.70000000000005 +172.95666666666668,-126.31666666666665,131.17499999999998,172.95666666666668,172.95666666666668,349.8 +173.0061111111111,-126.35277777777776,131.2125,173.0061111111111,173.0061111111111,349.90000000000003 +173.05555555555554,-126.38888888888887,131.25,173.05555555555554,173.05555555555554,350.0 +173.105,-126.42499999999998,131.2875,173.105,173.105,350.1 +173.15444444444444,-126.4611111111111,131.325,173.15444444444444,173.15444444444444,350.20000000000005 +173.20388888888888,-126.4972222222222,131.36249999999998,173.20388888888888,173.20388888888888,350.3 +173.25333333333333,-126.53333333333332,131.4,173.25333333333333,173.25333333333333,350.40000000000003 +173.30277777777778,-126.56944444444443,131.4375,173.30277777777778,173.30277777777778,350.5 +173.35222222222222,-126.60555555555554,131.475,173.35222222222222,173.35222222222222,350.6 +173.40166666666667,-126.64166666666665,131.5125,173.40166666666667,173.40166666666667,350.70000000000005 +173.45111111111112,-126.67777777777776,131.54999999999998,173.45111111111112,173.45111111111112,350.8 +173.50055555555556,-126.71388888888887,131.5875,173.50055555555556,173.50055555555556,350.90000000000003 +173.55,-126.74999999999999,131.625,173.55,173.55,351.0 +173.59944444444443,-126.7861111111111,131.6625,173.59944444444443,173.59944444444443,351.1 +173.64888888888888,-126.82222222222221,131.7,173.64888888888888,173.64888888888888,351.20000000000005 +173.69833333333332,-126.85833333333332,131.73749999999998,173.69833333333332,173.69833333333332,351.3 +173.74777777777777,-126.89444444444443,131.775,173.74777777777777,173.74777777777777,351.40000000000003 +173.79722222222222,-126.93055555555554,131.8125,173.79722222222222,173.79722222222222,351.5 +173.84666666666666,-126.96666666666665,131.85,173.84666666666666,173.84666666666666,351.6 +173.8961111111111,-127.00277777777777,131.8875,173.8961111111111,173.8961111111111,351.70000000000005 +173.94555555555556,-127.03888888888888,131.92499999999998,173.94555555555556,173.94555555555556,351.8 +173.995,-127.07499999999999,131.9625,173.995,173.995,351.90000000000003 +174.04444444444445,-127.1111111111111,132.0,174.04444444444445,174.04444444444445,352.0 +174.0938888888889,-127.14722222222221,132.0375,174.0938888888889,174.0938888888889,352.1 +174.14333333333332,-127.18333333333332,132.075,174.14333333333332,174.14333333333332,352.20000000000005 +174.19277777777776,-127.21944444444443,132.11249999999998,174.19277777777776,174.19277777777776,352.3 +174.2422222222222,-127.25555555555555,132.15,174.2422222222222,174.2422222222222,352.40000000000003 +174.29166666666666,-127.29166666666666,132.1875,174.29166666666666,174.29166666666666,352.5 +174.3411111111111,-127.32777777777777,132.225,174.3411111111111,174.3411111111111,352.6 +174.39055555555555,-127.36388888888888,132.2625,174.39055555555555,174.39055555555555,352.70000000000005 +174.44,-127.39999999999999,132.29999999999998,174.44,174.44,352.8 +174.48944444444444,-127.4361111111111,132.3375,174.48944444444444,174.48944444444444,352.90000000000003 +174.5388888888889,-127.47222222222221,132.375,174.5388888888889,174.5388888888889,353.0 +174.58833333333334,-127.50833333333333,132.4125,174.58833333333334,174.58833333333334,353.1 +174.63777777777779,-127.54444444444444,132.45,174.63777777777779,174.63777777777779,353.20000000000005 +174.68722222222223,-127.58055555555555,132.48749999999998,174.68722222222223,174.68722222222223,353.3 +174.73666666666665,-127.61666666666666,132.525,174.73666666666665,174.73666666666665,353.40000000000003 +174.7861111111111,-127.65277777777777,132.5625,174.7861111111111,174.7861111111111,353.5 +174.83555555555554,-127.68888888888888,132.6,174.83555555555554,174.83555555555554,353.6 +174.885,-127.725,132.6375,174.885,174.885,353.70000000000005 +174.93444444444444,-127.7611111111111,132.67499999999998,174.93444444444444,174.93444444444444,353.8 +174.98388888888888,-127.79722222222222,132.7125,174.98388888888888,174.98388888888888,353.90000000000003 +175.03333333333333,-127.83333333333331,132.75,175.03333333333333,175.03333333333333,354.0 +175.08277777777778,-127.86944444444443,132.7875,175.08277777777778,175.08277777777778,354.1 +175.13222222222223,-127.90555555555554,132.825,175.13222222222223,175.13222222222223,354.20000000000005 +175.18166666666667,-127.94166666666665,132.86249999999998,175.18166666666667,175.18166666666667,354.3 +175.23111111111112,-127.97777777777776,132.9,175.23111111111112,175.23111111111112,354.40000000000003 +175.28055555555557,-128.01388888888889,132.9375,175.28055555555557,175.28055555555557,354.5 +175.32999999999998,-128.04999999999998,132.975,175.32999999999998,175.32999999999998,354.6 +175.37944444444443,-128.0861111111111,133.0125,175.37944444444443,175.37944444444443,354.70000000000005 +175.42888888888888,-128.1222222222222,133.04999999999998,175.42888888888888,175.42888888888888,354.8 +175.47833333333332,-128.15833333333333,133.0875,175.47833333333332,175.47833333333332,354.90000000000003 +175.52777777777777,-128.19444444444443,133.125,175.52777777777777,175.52777777777777,355.0 +175.57722222222222,-128.23055555555555,133.1625,175.57722222222222,175.57722222222222,355.1 +175.62666666666667,-128.26666666666665,133.2,175.62666666666667,175.62666666666667,355.20000000000005 +175.6761111111111,-128.30277777777778,133.23749999999998,175.6761111111111,175.6761111111111,355.3 +175.72555555555556,-128.33888888888887,133.275,175.72555555555556,175.72555555555556,355.40000000000003 +175.775,-128.375,133.3125,175.775,175.775,355.5 +175.82444444444445,-128.4111111111111,133.35,175.82444444444445,175.82444444444445,355.6 +175.8738888888889,-128.44722222222222,133.3875,175.8738888888889,175.8738888888889,355.70000000000005 +175.92333333333332,-128.48333333333332,133.42499999999998,175.92333333333332,175.92333333333332,355.8 +175.97277777777776,-128.51944444444445,133.4625,175.97277777777776,175.97277777777776,355.90000000000003 +176.0222222222222,-128.55555555555554,133.5,176.0222222222222,176.0222222222222,356.0 +176.07166666666666,-128.59166666666667,133.5375,176.07166666666666,176.07166666666666,356.1 +176.1211111111111,-128.62777777777777,133.575,176.1211111111111,176.1211111111111,356.20000000000005 +176.17055555555555,-128.66388888888886,133.61249999999998,176.17055555555555,176.17055555555555,356.3 +176.22,-128.7,133.65,176.22,176.22,356.40000000000003 +176.26944444444445,-128.7361111111111,133.6875,176.26944444444445,176.26944444444445,356.5 +176.3188888888889,-128.7722222222222,133.725,176.3188888888889,176.3188888888889,356.6 +176.36833333333334,-128.8083333333333,133.7625,176.36833333333334,176.36833333333334,356.70000000000005 +176.4177777777778,-128.84444444444443,133.79999999999998,176.4177777777778,176.4177777777778,356.8 +176.46722222222223,-128.88055555555553,133.8375,176.46722222222223,176.46722222222223,356.90000000000003 +176.51666666666665,-128.91666666666666,133.875,176.51666666666665,176.51666666666665,357.0 +176.5661111111111,-128.95277777777775,133.9125,176.5661111111111,176.5661111111111,357.1 +176.61555555555555,-128.98888888888888,133.95,176.61555555555555,176.61555555555555,357.20000000000005 +176.665,-129.02499999999998,133.98749999999998,176.665,176.665,357.3 +176.71444444444444,-129.0611111111111,134.025,176.71444444444444,176.71444444444444,357.40000000000003 +176.76388888888889,-129.0972222222222,134.0625,176.76388888888889,176.76388888888889,357.5 +176.81333333333333,-129.13333333333333,134.1,176.81333333333333,176.81333333333333,357.6 +176.86277777777778,-129.16944444444442,134.1375,176.86277777777778,176.86277777777778,357.70000000000005 +176.91222222222223,-129.20555555555555,134.17499999999998,176.91222222222223,176.91222222222223,357.8 +176.96166666666667,-129.24166666666665,134.2125,176.96166666666667,176.96166666666667,357.90000000000003 +177.01111111111112,-129.27777777777777,134.25,177.01111111111112,177.01111111111112,358.0 +177.06055555555557,-129.31388888888887,134.2875,177.06055555555557,177.06055555555557,358.1 +177.10999999999999,-129.35,134.325,177.10999999999999,177.10999999999999,358.20000000000005 +177.15944444444443,-129.3861111111111,134.36249999999998,177.15944444444443,177.15944444444443,358.3 +177.20888888888888,-129.42222222222222,134.4,177.20888888888888,177.20888888888888,358.40000000000003 +177.25833333333333,-129.45833333333331,134.4375,177.25833333333333,177.25833333333333,358.5 +177.30777777777777,-129.49444444444444,134.475,177.30777777777777,177.30777777777777,358.6 +177.35722222222222,-129.53055555555554,134.5125,177.35722222222222,177.35722222222222,358.70000000000005 +177.40666666666667,-129.56666666666666,134.54999999999998,177.40666666666667,177.40666666666667,358.8 +177.4561111111111,-129.60277777777776,134.5875,177.4561111111111,177.4561111111111,358.90000000000003 +177.50555555555556,-129.63888888888889,134.625,177.50555555555556,177.50555555555556,359.0 +177.555,-129.67499999999998,134.6625,177.555,177.555,359.1 +177.60444444444445,-129.7111111111111,134.7,177.60444444444445,177.60444444444445,359.20000000000005 +177.65388888888887,-129.7472222222222,134.73749999999998,177.65388888888887,177.65388888888887,359.3 +177.70333333333332,-129.78333333333333,134.775,177.70333333333332,177.70333333333332,359.40000000000003 +177.75277777777777,-129.81944444444443,134.8125,177.75277777777777,177.75277777777777,359.5 +177.8022222222222,-129.85555555555555,134.85,177.8022222222222,177.8022222222222,359.6 +177.85166666666666,-129.89166666666665,134.8875,177.85166666666666,177.85166666666666,359.70000000000005 +177.9011111111111,-129.92777777777778,134.92499999999998,177.9011111111111,177.9011111111111,359.8 +177.95055555555555,-129.96388888888887,134.9625,177.95055555555555,177.95055555555555,359.90000000000003 +178,-130,135,178,178,360 diff --git a/rm_arm_control/data/RM65&RM63_canfd_data.txt b/rm_arm_control/data/RM65&RM63_canfd_data.txt new file mode 100644 index 0000000..a6821c1 --- /dev/null +++ b/rm_arm_control/data/RM65&RM63_canfd_data.txt @@ -0,0 +1,3600 @@ +0.049444444444444444,-0.03611111111111111,0.0375,0.049444444444444444,0.035555555555555556,0.1 +0.09888888888888889,-0.07222222222222222,0.075,0.09888888888888889,0.07111111111111111,0.2 +0.14833333333333332,-0.10833333333333332,0.11249999999999999,0.14833333333333332,0.10666666666666666,0.30000000000000004 +0.19777777777777777,-0.14444444444444443,0.15,0.19777777777777777,0.14222222222222222,0.4 +0.24722222222222223,-0.18055555555555552,0.1875,0.24722222222222223,0.17777777777777778,0.5 +0.29666666666666663,-0.21666666666666665,0.22499999999999998,0.29666666666666663,0.21333333333333332,0.6000000000000001 +0.3461111111111111,-0.25277777777777777,0.2625,0.3461111111111111,0.24888888888888888,0.7000000000000001 +0.39555555555555555,-0.28888888888888886,0.3,0.39555555555555555,0.28444444444444444,0.8 +0.445,-0.32499999999999996,0.33749999999999997,0.445,0.32,0.9 +0.49444444444444446,-0.36111111111111105,0.375,0.49444444444444446,0.35555555555555557,1.0 +0.5438888888888889,-0.3972222222222222,0.4125,0.5438888888888889,0.39111111111111113,1.1 +0.5933333333333333,-0.4333333333333333,0.44999999999999996,0.5933333333333333,0.42666666666666664,1.2000000000000002 +0.6427777777777778,-0.4694444444444444,0.4875,0.6427777777777778,0.4622222222222222,1.3 +0.6922222222222222,-0.5055555555555555,0.525,0.6922222222222222,0.49777777777777776,1.4000000000000001 +0.7416666666666667,-0.5416666666666666,0.5625,0.7416666666666667,0.5333333333333333,1.5 +0.7911111111111111,-0.5777777777777777,0.6,0.7911111111111111,0.5688888888888889,1.6 +0.8405555555555555,-0.6138888888888888,0.6375,0.8405555555555555,0.6044444444444445,1.7000000000000002 +0.89,-0.6499999999999999,0.6749999999999999,0.89,0.64,1.8 +0.9394444444444444,-0.686111111111111,0.7125,0.9394444444444444,0.6755555555555556,1.9000000000000001 +0.9888888888888889,-0.7222222222222221,0.75,0.9888888888888889,0.7111111111111111,2.0 +1.0383333333333333,-0.7583333333333333,0.7875,1.0383333333333333,0.7466666666666667,2.1 +1.0877777777777777,-0.7944444444444444,0.825,1.0877777777777777,0.7822222222222223,2.2 +1.1372222222222221,-0.8305555555555555,0.8624999999999999,1.1372222222222221,0.8177777777777778,2.3000000000000003 +1.1866666666666665,-0.8666666666666666,0.8999999999999999,1.1866666666666665,0.8533333333333333,2.4000000000000004 +1.2361111111111112,-0.9027777777777777,0.9375,1.2361111111111112,0.8888888888888888,2.5 +1.2855555555555556,-0.9388888888888888,0.975,1.2855555555555556,0.9244444444444444,2.6 +1.335,-0.9749999999999999,1.0125,1.335,0.96,2.7 +1.3844444444444444,-1.011111111111111,1.05,1.3844444444444444,0.9955555555555555,2.8000000000000003 +1.4338888888888888,-1.047222222222222,1.0875,1.4338888888888888,1.031111111111111,2.9000000000000004 +1.4833333333333334,-1.0833333333333333,1.125,1.4833333333333334,1.0666666666666667,3.0 +1.5327777777777778,-1.1194444444444442,1.1624999999999999,1.5327777777777778,1.1022222222222222,3.1 +1.5822222222222222,-1.1555555555555554,1.2,1.5822222222222222,1.1377777777777778,3.2 +1.6316666666666666,-1.1916666666666667,1.2375,1.6316666666666666,1.1733333333333333,3.3000000000000003 +1.681111111111111,-1.2277777777777776,1.275,1.681111111111111,1.208888888888889,3.4000000000000004 +1.7305555555555556,-1.2638888888888888,1.3125,1.7305555555555556,1.2444444444444445,3.5 +1.78,-1.2999999999999998,1.3499999999999999,1.78,1.28,3.6 +1.8294444444444444,-1.336111111111111,1.3875,1.8294444444444444,1.3155555555555556,3.7 +1.8788888888888888,-1.372222222222222,1.425,1.8788888888888888,1.3511111111111112,3.8000000000000003 +1.9283333333333332,-1.4083333333333332,1.4625,1.9283333333333332,1.3866666666666667,3.9000000000000004 +1.9777777777777779,-1.4444444444444442,1.5,1.9777777777777779,1.4222222222222223,4.0 +2.027222222222222,-1.4805555555555554,1.5374999999999999,2.027222222222222,1.4577777777777778,4.1000000000000005 +2.0766666666666667,-1.5166666666666666,1.575,2.0766666666666667,1.4933333333333334,4.2 +2.1261111111111113,-1.5527777777777776,1.6125,2.1261111111111113,1.528888888888889,4.3 +2.1755555555555555,-1.5888888888888888,1.65,2.1755555555555555,1.5644444444444445,4.4 +2.225,-1.6249999999999998,1.6875,2.225,1.6,4.5 +2.2744444444444443,-1.661111111111111,1.7249999999999999,2.2744444444444443,1.6355555555555557,4.6000000000000005 +2.323888888888889,-1.697222222222222,1.7625,2.323888888888889,1.6711111111111112,4.7 +2.373333333333333,-1.7333333333333332,1.7999999999999998,2.373333333333333,1.7066666666666666,4.800000000000001 +2.4227777777777777,-1.7694444444444444,1.8375,2.4227777777777777,1.7422222222222221,4.9 +2.4722222222222223,-1.8055555555555554,1.875,2.4722222222222223,1.7777777777777777,5.0 +2.5216666666666665,-1.8416666666666666,1.9124999999999999,2.5216666666666665,1.8133333333333332,5.1000000000000005 +2.571111111111111,-1.8777777777777775,1.95,2.571111111111111,1.8488888888888888,5.2 +2.6205555555555553,-1.9138888888888888,1.9874999999999998,2.6205555555555553,1.8844444444444444,5.300000000000001 +2.67,-1.9499999999999997,2.025,2.67,1.92,5.4 +2.7194444444444446,-1.986111111111111,2.0625,2.7194444444444446,1.9555555555555555,5.5 +2.7688888888888887,-2.022222222222222,2.1,2.7688888888888887,1.991111111111111,5.6000000000000005 +2.8183333333333334,-2.058333333333333,2.1374999999999997,2.8183333333333334,2.026666666666667,5.7 +2.8677777777777775,-2.094444444444444,2.175,2.8677777777777775,2.062222222222222,5.800000000000001 +2.917222222222222,-2.1305555555555555,2.2125,2.917222222222222,2.097777777777778,5.9 +2.966666666666667,-2.1666666666666665,2.25,2.966666666666667,2.1333333333333333,6.0 +3.016111111111111,-2.2027777777777775,2.2875,3.016111111111111,2.168888888888889,6.1000000000000005 +3.0655555555555556,-2.2388888888888885,2.3249999999999997,3.0655555555555556,2.2044444444444444,6.2 +3.1149999999999998,-2.275,2.3625,3.1149999999999998,2.24,6.300000000000001 +3.1644444444444444,-2.311111111111111,2.4,3.1644444444444444,2.2755555555555556,6.4 +3.213888888888889,-2.347222222222222,2.4375,3.213888888888889,2.311111111111111,6.5 +3.263333333333333,-2.3833333333333333,2.475,3.263333333333333,2.3466666666666667,6.6000000000000005 +3.312777777777778,-2.4194444444444443,2.5124999999999997,3.312777777777778,2.382222222222222,6.7 +3.362222222222222,-2.4555555555555553,2.55,3.362222222222222,2.417777777777778,6.800000000000001 +3.4116666666666666,-2.4916666666666663,2.5875,3.4116666666666666,2.453333333333333,6.9 +3.4611111111111112,-2.5277777777777777,2.625,3.4611111111111112,2.488888888888889,7.0 +3.5105555555555554,-2.5638888888888887,2.6625,3.5105555555555554,2.5244444444444443,7.1000000000000005 +3.56,-2.5999999999999996,2.6999999999999997,3.56,2.56,7.2 +3.6094444444444442,-2.636111111111111,2.7375,3.6094444444444442,2.5955555555555554,7.300000000000001 +3.658888888888889,-2.672222222222222,2.775,3.658888888888889,2.631111111111111,7.4 +3.7083333333333335,-2.708333333333333,2.8125,3.7083333333333335,2.6666666666666665,7.5 +3.7577777777777777,-2.744444444444444,2.85,3.7577777777777777,2.7022222222222223,7.6000000000000005 +3.8072222222222223,-2.7805555555555554,2.8874999999999997,3.8072222222222223,2.7377777777777776,7.7 +3.8566666666666665,-2.8166666666666664,2.925,3.8566666666666665,2.7733333333333334,7.800000000000001 +3.906111111111111,-2.8527777777777774,2.9625,3.906111111111111,2.8088888888888888,7.9 +3.9555555555555557,-2.8888888888888884,3.0,3.9555555555555557,2.8444444444444446,8.0 +4.005,-2.925,3.0375,4.005,2.88,8.1 +4.054444444444444,-2.961111111111111,3.0749999999999997,4.054444444444444,2.9155555555555557,8.200000000000001 +4.103888888888889,-2.997222222222222,3.1125,4.103888888888889,2.951111111111111,8.3 +4.153333333333333,-3.033333333333333,3.15,4.153333333333333,2.986666666666667,8.4 +4.2027777777777775,-3.069444444444444,3.1875,4.2027777777777775,3.022222222222222,8.5 +4.252222222222223,-3.105555555555555,3.225,4.252222222222223,3.057777777777778,8.6 +4.301666666666667,-3.141666666666666,3.2624999999999997,4.301666666666667,3.0933333333333333,8.700000000000001 +4.351111111111111,-3.1777777777777776,3.3,4.351111111111111,3.128888888888889,8.8 +4.400555555555555,-3.2138888888888886,3.3375,4.400555555555555,3.1644444444444444,8.9 +4.45,-3.2499999999999996,3.375,4.45,3.2,9.0 +4.499444444444444,-3.286111111111111,3.4125,4.499444444444444,3.2355555555555555,9.1 +4.5488888888888885,-3.322222222222222,3.4499999999999997,4.5488888888888885,3.2711111111111113,9.200000000000001 +4.598333333333334,-3.358333333333333,3.4875,4.598333333333334,3.3066666666666666,9.3 +4.647777777777778,-3.394444444444444,3.525,4.647777777777778,3.3422222222222224,9.4 +4.697222222222222,-3.4305555555555554,3.5625,4.697222222222222,3.3777777777777778,9.5 +4.746666666666666,-3.4666666666666663,3.5999999999999996,4.746666666666666,3.413333333333333,9.600000000000001 +4.796111111111111,-3.5027777777777773,3.6374999999999997,4.796111111111111,3.448888888888889,9.700000000000001 +4.845555555555555,-3.5388888888888888,3.675,4.845555555555555,3.4844444444444442,9.8 +4.895,-3.5749999999999997,3.7125,4.895,3.52,9.9 +4.944444444444445,-3.6111111111111107,3.75,4.944444444444445,3.5555555555555554,10.0 +4.993888888888889,-3.6472222222222217,3.7874999999999996,4.993888888888889,3.591111111111111,10.100000000000001 +5.043333333333333,-3.683333333333333,3.8249999999999997,5.043333333333333,3.6266666666666665,10.200000000000001 +5.092777777777778,-3.719444444444444,3.8625,5.092777777777778,3.6622222222222223,10.3 +5.142222222222222,-3.755555555555555,3.9,5.142222222222222,3.6977777777777776,10.4 +5.191666666666666,-3.7916666666666665,3.9375,5.191666666666666,3.7333333333333334,10.5 +5.241111111111111,-3.8277777777777775,3.9749999999999996,5.241111111111111,3.7688888888888887,10.600000000000001 +5.290555555555556,-3.8638888888888885,4.0125,5.290555555555556,3.8044444444444445,10.700000000000001 +5.34,-3.8999999999999995,4.05,5.34,3.84,10.8 +5.389444444444444,-3.936111111111111,4.0874999999999995,5.389444444444444,3.8755555555555556,10.9 +5.438888888888889,-3.972222222222222,4.125,5.438888888888889,3.911111111111111,11.0 +5.488333333333333,-4.008333333333333,4.1625,5.488333333333333,3.9466666666666668,11.100000000000001 +5.5377777777777775,-4.044444444444444,4.2,5.5377777777777775,3.982222222222222,11.200000000000001 +5.5872222222222225,-4.080555555555555,4.2375,5.5872222222222225,4.017777777777778,11.3 +5.636666666666667,-4.116666666666666,4.2749999999999995,5.636666666666667,4.053333333333334,11.4 +5.686111111111111,-4.152777777777778,4.3125,5.686111111111111,4.088888888888889,11.5 +5.735555555555555,-4.188888888888888,4.35,5.735555555555555,4.124444444444444,11.600000000000001 +5.785,-4.225,4.3875,5.785,4.16,11.700000000000001 +5.834444444444444,-4.261111111111111,4.425,5.834444444444444,4.195555555555556,11.8 +5.8838888888888885,-4.297222222222222,4.4624999999999995,5.8838888888888885,4.231111111111111,11.9 +5.933333333333334,-4.333333333333333,4.5,5.933333333333334,4.266666666666667,12.0 +5.982777777777778,-4.3694444444444445,4.5375,5.982777777777778,4.302222222222222,12.100000000000001 +6.032222222222222,-4.405555555555555,4.575,6.032222222222222,4.337777777777778,12.200000000000001 +6.081666666666667,-4.441666666666666,4.6125,6.081666666666667,4.373333333333333,12.3 +6.131111111111111,-4.477777777777777,4.6499999999999995,6.131111111111111,4.408888888888889,12.4 +6.180555555555555,-4.513888888888888,4.6875,6.180555555555555,4.444444444444445,12.5 +6.2299999999999995,-4.55,4.725,6.2299999999999995,4.48,12.600000000000001 +6.279444444444445,-4.58611111111111,4.7625,6.279444444444445,4.515555555555555,12.700000000000001 +6.328888888888889,-4.622222222222222,4.8,6.328888888888889,4.551111111111111,12.8 +6.378333333333333,-4.658333333333333,4.8374999999999995,6.378333333333333,4.586666666666667,12.9 +6.427777777777778,-4.694444444444444,4.875,6.427777777777778,4.622222222222222,13.0 +6.477222222222222,-4.730555555555555,4.9125,6.477222222222222,4.657777777777778,13.100000000000001 +6.526666666666666,-4.766666666666667,4.95,6.526666666666666,4.693333333333333,13.200000000000001 +6.576111111111111,-4.802777777777777,4.9875,6.576111111111111,4.728888888888889,13.3 +6.625555555555556,-4.838888888888889,5.0249999999999995,6.625555555555556,4.764444444444444,13.4 +6.675,-4.874999999999999,5.0625,6.675,4.8,13.5 +6.724444444444444,-4.9111111111111105,5.1,6.724444444444444,4.835555555555556,13.600000000000001 +6.773888888888889,-4.947222222222222,5.1375,6.773888888888889,4.871111111111111,13.700000000000001 +6.823333333333333,-4.9833333333333325,5.175,6.823333333333333,4.906666666666666,13.8 +6.872777777777777,-5.019444444444444,5.2124999999999995,6.872777777777777,4.942222222222222,13.9 +6.9222222222222225,-5.055555555555555,5.25,6.9222222222222225,4.977777777777778,14.0 +6.971666666666667,-5.091666666666666,5.2875,6.971666666666667,5.013333333333334,14.100000000000001 +7.021111111111111,-5.127777777777777,5.325,7.021111111111111,5.0488888888888885,14.200000000000001 +7.070555555555555,-5.163888888888889,5.3625,7.070555555555555,5.084444444444444,14.3 +7.12,-5.199999999999999,5.3999999999999995,7.12,5.12,14.4 +7.169444444444444,-5.236111111111111,5.4375,7.169444444444444,5.155555555555556,14.5 +7.2188888888888885,-5.272222222222222,5.475,7.2188888888888885,5.191111111111111,14.600000000000001 +7.2683333333333335,-5.308333333333333,5.5125,7.2683333333333335,5.226666666666667,14.700000000000001 +7.317777777777778,-5.344444444444444,5.55,7.317777777777778,5.262222222222222,14.8 +7.367222222222222,-5.380555555555555,5.5874999999999995,7.367222222222222,5.297777777777778,14.9 +7.416666666666667,-5.416666666666666,5.625,7.416666666666667,5.333333333333333,15.0 +7.466111111111111,-5.4527777777777775,5.6625,7.466111111111111,5.368888888888889,15.100000000000001 +7.515555555555555,-5.488888888888888,5.7,7.515555555555555,5.404444444444445,15.200000000000001 +7.5649999999999995,-5.5249999999999995,5.7375,7.5649999999999995,5.44,15.3 +7.614444444444445,-5.561111111111111,5.7749999999999995,7.614444444444445,5.475555555555555,15.4 +7.663888888888889,-5.597222222222221,5.8125,7.663888888888889,5.511111111111111,15.5 +7.713333333333333,-5.633333333333333,5.85,7.713333333333333,5.546666666666667,15.600000000000001 +7.762777777777778,-5.669444444444444,5.8875,7.762777777777778,5.582222222222223,15.700000000000001 +7.812222222222222,-5.705555555555555,5.925,7.812222222222222,5.6177777777777775,15.8 +7.861666666666666,-5.741666666666666,5.9624999999999995,7.861666666666666,5.653333333333333,15.9 +7.911111111111111,-5.777777777777777,6.0,7.911111111111111,5.688888888888889,16.0 +7.960555555555556,-5.813888888888888,6.0375,7.960555555555556,5.724444444444444,16.1 +8.01,-5.85,6.075,8.01,5.76,16.2 +8.059444444444445,-5.88611111111111,6.1125,8.059444444444445,5.795555555555556,16.3 +8.108888888888888,-5.922222222222222,6.1499999999999995,8.108888888888888,5.831111111111111,16.400000000000002 +8.158333333333333,-5.958333333333333,6.1875,8.158333333333333,5.866666666666666,16.5 +8.207777777777778,-5.994444444444444,6.225,8.207777777777778,5.902222222222222,16.6 +8.257222222222222,-6.030555555555555,6.2625,8.257222222222222,5.937777777777778,16.7 +8.306666666666667,-6.066666666666666,6.3,8.306666666666667,5.973333333333334,16.8 +8.356111111111112,-6.102777777777777,6.3374999999999995,8.356111111111112,6.0088888888888885,16.900000000000002 +8.405555555555555,-6.138888888888888,6.375,8.405555555555555,6.044444444444444,17.0 +8.455,-6.175,6.4125,8.455,6.08,17.1 +8.504444444444445,-6.21111111111111,6.45,8.504444444444445,6.115555555555556,17.2 +8.553888888888888,-6.247222222222222,6.4875,8.553888888888888,6.151111111111111,17.3 +8.603333333333333,-6.283333333333332,6.5249999999999995,8.603333333333333,6.1866666666666665,17.400000000000002 +8.652777777777777,-6.319444444444444,6.5625,8.652777777777777,6.222222222222222,17.5 +8.702222222222222,-6.355555555555555,6.6,8.702222222222222,6.257777777777778,17.6 +8.751666666666667,-6.391666666666666,6.6375,8.751666666666667,6.293333333333333,17.7 +8.80111111111111,-6.427777777777777,6.675,8.80111111111111,6.328888888888889,17.8 +8.850555555555555,-6.463888888888889,6.7124999999999995,8.850555555555555,6.364444444444445,17.900000000000002 +8.9,-6.499999999999999,6.75,8.9,6.4,18.0 +8.949444444444444,-6.5361111111111105,6.7875,8.949444444444444,6.435555555555555,18.1 +8.998888888888889,-6.572222222222222,6.825,8.998888888888889,6.471111111111111,18.2 +9.048333333333334,-6.6083333333333325,6.8625,9.048333333333334,6.506666666666667,18.3 +9.097777777777777,-6.644444444444444,6.8999999999999995,9.097777777777777,6.542222222222223,18.400000000000002 +9.147222222222222,-6.680555555555555,6.9375,9.147222222222222,6.5777777777777775,18.5 +9.196666666666667,-6.716666666666666,6.975,9.196666666666667,6.613333333333333,18.6 +9.24611111111111,-6.752777777777777,7.0125,9.24611111111111,6.648888888888889,18.7 +9.295555555555556,-6.788888888888888,7.05,9.295555555555556,6.684444444444445,18.8 +9.345,-6.824999999999999,7.0874999999999995,9.345,6.72,18.900000000000002 +9.394444444444444,-6.861111111111111,7.125,9.394444444444444,6.7555555555555555,19.0 +9.443888888888889,-6.897222222222221,7.1625,9.443888888888889,6.791111111111111,19.1 +9.493333333333332,-6.933333333333333,7.199999999999999,9.493333333333332,6.826666666666666,19.200000000000003 +9.542777777777777,-6.969444444444444,7.2375,9.542777777777777,6.862222222222222,19.3 +9.592222222222222,-7.005555555555555,7.2749999999999995,9.592222222222222,6.897777777777778,19.400000000000002 +9.641666666666666,-7.041666666666666,7.3125,9.641666666666666,6.933333333333334,19.5 +9.69111111111111,-7.0777777777777775,7.35,9.69111111111111,6.9688888888888885,19.6 +9.740555555555556,-7.113888888888888,7.387499999999999,9.740555555555556,7.004444444444444,19.700000000000003 +9.79,-7.1499999999999995,7.425,9.79,7.04,19.8 +9.839444444444444,-7.18611111111111,7.4624999999999995,9.839444444444444,7.075555555555556,19.900000000000002 +9.88888888888889,-7.222222222222221,7.5,9.88888888888889,7.111111111111111,20.0 +9.938333333333333,-7.258333333333333,7.5375,9.938333333333333,7.1466666666666665,20.1 +9.987777777777778,-7.294444444444443,7.574999999999999,9.987777777777778,7.182222222222222,20.200000000000003 +10.037222222222223,-7.330555555555555,7.6125,10.037222222222223,7.217777777777778,20.3 +10.086666666666666,-7.366666666666666,7.6499999999999995,10.086666666666666,7.253333333333333,20.400000000000002 +10.136111111111111,-7.402777777777777,7.6875,10.136111111111111,7.288888888888889,20.5 +10.185555555555556,-7.438888888888888,7.725,10.185555555555556,7.3244444444444445,20.6 +10.235,-7.475,7.762499999999999,10.235,7.36,20.700000000000003 +10.284444444444444,-7.51111111111111,7.8,10.284444444444444,7.395555555555555,20.8 +10.33388888888889,-7.547222222222222,7.8374999999999995,10.33388888888889,7.431111111111111,20.900000000000002 +10.383333333333333,-7.583333333333333,7.875,10.383333333333333,7.466666666666667,21.0 +10.432777777777778,-7.619444444444444,7.9125,10.432777777777778,7.502222222222223,21.1 +10.482222222222221,-7.655555555555555,7.949999999999999,10.482222222222221,7.5377777777777775,21.200000000000003 +10.531666666666666,-7.6916666666666655,7.9875,10.531666666666666,7.573333333333333,21.3 +10.581111111111111,-7.727777777777777,8.025,10.581111111111111,7.608888888888889,21.400000000000002 +10.630555555555555,-7.763888888888888,8.0625,10.630555555555555,7.644444444444445,21.5 +10.68,-7.799999999999999,8.1,10.68,7.68,21.6 +10.729444444444445,-7.83611111111111,8.1375,10.729444444444445,7.7155555555555555,21.700000000000003 +10.778888888888888,-7.872222222222222,8.174999999999999,10.778888888888888,7.751111111111111,21.8 +10.828333333333333,-7.908333333333332,8.2125,10.828333333333333,7.786666666666667,21.900000000000002 +10.877777777777778,-7.944444444444444,8.25,10.877777777777778,7.822222222222222,22.0 +10.927222222222222,-7.980555555555555,8.2875,10.927222222222222,7.857777777777778,22.1 +10.976666666666667,-8.016666666666666,8.325,10.976666666666667,7.8933333333333335,22.200000000000003 +11.026111111111112,-8.052777777777777,8.362499999999999,11.026111111111112,7.928888888888889,22.3 +11.075555555555555,-8.088888888888889,8.4,11.075555555555555,7.964444444444444,22.400000000000002 +11.125,-8.125,8.4375,11.125,8.0,22.5 +11.174444444444445,-8.16111111111111,8.475,11.174444444444445,8.035555555555556,22.6 +11.223888888888888,-8.197222222222221,8.5125,11.223888888888888,8.071111111111112,22.700000000000003 +11.273333333333333,-8.233333333333333,8.549999999999999,11.273333333333333,8.106666666666667,22.8 +11.322777777777777,-8.269444444444444,8.5875,11.322777777777777,8.142222222222221,22.900000000000002 +11.372222222222222,-8.305555555555555,8.625,11.372222222222222,8.177777777777777,23.0 +11.421666666666667,-8.341666666666665,8.6625,11.421666666666667,8.213333333333333,23.1 +11.47111111111111,-8.377777777777776,8.7,11.47111111111111,8.248888888888889,23.200000000000003 +11.520555555555555,-8.413888888888888,8.737499999999999,11.520555555555555,8.284444444444444,23.3 +11.57,-8.45,8.775,11.57,8.32,23.400000000000002 +11.619444444444444,-8.48611111111111,8.8125,11.619444444444444,8.355555555555556,23.5 +11.668888888888889,-8.522222222222222,8.85,11.668888888888889,8.391111111111112,23.6 +11.718333333333334,-8.558333333333332,8.8875,11.718333333333334,8.426666666666666,23.700000000000003 +11.767777777777777,-8.594444444444443,8.924999999999999,11.767777777777777,8.462222222222222,23.8 +11.817222222222222,-8.630555555555555,8.9625,11.817222222222222,8.497777777777777,23.900000000000002 +11.866666666666667,-8.666666666666666,9.0,11.866666666666667,8.533333333333333,24.0 +11.91611111111111,-8.702777777777778,9.0375,11.91611111111111,8.568888888888889,24.1 +11.965555555555556,-8.738888888888889,9.075,11.965555555555556,8.604444444444445,24.200000000000003 +12.015,-8.774999999999999,9.112499999999999,12.015,8.64,24.3 +12.064444444444444,-8.81111111111111,9.15,12.064444444444444,8.675555555555556,24.400000000000002 +12.113888888888889,-8.847222222222221,9.1875,12.113888888888889,8.71111111111111,24.5 +12.163333333333334,-8.883333333333333,9.225,12.163333333333334,8.746666666666666,24.6 +12.212777777777777,-8.919444444444444,9.2625,12.212777777777777,8.782222222222222,24.700000000000003 +12.262222222222222,-8.955555555555554,9.299999999999999,12.262222222222222,8.817777777777778,24.8 +12.311666666666666,-8.991666666666665,9.3375,12.311666666666666,8.853333333333333,24.900000000000002 +12.36111111111111,-9.027777777777777,9.375,12.36111111111111,8.88888888888889,25.0 +12.410555555555556,-9.063888888888888,9.4125,12.410555555555556,8.924444444444445,25.1 +12.459999999999999,-9.1,9.45,12.459999999999999,8.96,25.200000000000003 +12.509444444444444,-9.136111111111111,9.487499999999999,12.509444444444444,8.995555555555555,25.3 +12.55888888888889,-9.17222222222222,9.525,12.55888888888889,9.03111111111111,25.400000000000002 +12.608333333333333,-9.208333333333332,9.5625,12.608333333333333,9.066666666666666,25.5 +12.657777777777778,-9.244444444444444,9.6,12.657777777777778,9.102222222222222,25.6 +12.707222222222223,-9.280555555555555,9.6375,12.707222222222223,9.137777777777778,25.700000000000003 +12.756666666666666,-9.316666666666666,9.674999999999999,12.756666666666666,9.173333333333334,25.8 +12.806111111111111,-9.352777777777776,9.7125,12.806111111111111,9.20888888888889,25.900000000000002 +12.855555555555556,-9.388888888888888,9.75,12.855555555555556,9.244444444444444,26.0 +12.905,-9.424999999999999,9.7875,12.905,9.28,26.1 +12.954444444444444,-9.46111111111111,9.825,12.954444444444444,9.315555555555555,26.200000000000003 +13.00388888888889,-9.497222222222222,9.862499999999999,13.00388888888889,9.351111111111111,26.3 +13.053333333333333,-9.533333333333333,9.9,13.053333333333333,9.386666666666667,26.400000000000002 +13.102777777777778,-9.569444444444443,9.9375,13.102777777777778,9.422222222222222,26.5 +13.152222222222221,-9.605555555555554,9.975,13.152222222222221,9.457777777777778,26.6 +13.201666666666666,-9.641666666666666,10.0125,13.201666666666666,9.493333333333334,26.700000000000003 +13.251111111111111,-9.677777777777777,10.049999999999999,13.251111111111111,9.528888888888888,26.8 +13.300555555555555,-9.713888888888889,10.0875,13.300555555555555,9.564444444444444,26.900000000000002 +13.35,-9.749999999999998,10.125,13.35,9.6,27.0 +13.399444444444445,-9.78611111111111,10.1625,13.399444444444445,9.635555555555555,27.1 +13.448888888888888,-9.822222222222221,10.2,13.448888888888888,9.671111111111111,27.200000000000003 +13.498333333333333,-9.858333333333333,10.237499999999999,13.498333333333333,9.706666666666667,27.3 +13.547777777777778,-9.894444444444444,10.275,13.547777777777778,9.742222222222223,27.400000000000002 +13.597222222222221,-9.930555555555555,10.3125,13.597222222222221,9.777777777777779,27.5 +13.646666666666667,-9.966666666666665,10.35,13.646666666666667,9.813333333333333,27.6 +13.696111111111112,-10.002777777777776,10.3875,13.696111111111112,9.848888888888888,27.700000000000003 +13.745555555555555,-10.038888888888888,10.424999999999999,13.745555555555555,9.884444444444444,27.8 +13.795,-10.075,10.4625,13.795,9.92,27.900000000000002 +13.844444444444445,-10.11111111111111,10.5,13.844444444444445,9.955555555555556,28.0 +13.893888888888888,-10.147222222222222,10.5375,13.893888888888888,9.991111111111111,28.1 +13.943333333333333,-10.183333333333332,10.575,13.943333333333333,10.026666666666667,28.200000000000003 +13.992777777777778,-10.219444444444443,10.612499999999999,13.992777777777778,10.062222222222223,28.3 +14.042222222222222,-10.255555555555555,10.65,14.042222222222222,10.097777777777777,28.400000000000002 +14.091666666666667,-10.291666666666666,10.6875,14.091666666666667,10.133333333333333,28.5 +14.14111111111111,-10.327777777777778,10.725,14.14111111111111,10.168888888888889,28.6 +14.190555555555555,-10.363888888888887,10.7625,14.190555555555555,10.204444444444444,28.700000000000003 +14.24,-10.399999999999999,10.799999999999999,14.24,10.24,28.8 +14.289444444444444,-10.43611111111111,10.8375,14.289444444444444,10.275555555555556,28.900000000000002 +14.338888888888889,-10.472222222222221,10.875,14.338888888888889,10.311111111111112,29.0 +14.388333333333334,-10.508333333333333,10.9125,14.388333333333334,10.346666666666666,29.1 +14.437777777777777,-10.544444444444444,10.95,14.437777777777777,10.382222222222222,29.200000000000003 +14.487222222222222,-10.580555555555554,10.987499999999999,14.487222222222222,10.417777777777777,29.3 +14.536666666666667,-10.616666666666665,11.025,14.536666666666667,10.453333333333333,29.400000000000002 +14.58611111111111,-10.652777777777777,11.0625,14.58611111111111,10.488888888888889,29.5 +14.635555555555555,-10.688888888888888,11.1,14.635555555555555,10.524444444444445,29.6 +14.685,-10.725,11.1375,14.685,10.56,29.700000000000003 +14.734444444444444,-10.76111111111111,11.174999999999999,14.734444444444444,10.595555555555556,29.8 +14.783888888888889,-10.79722222222222,11.2125,14.783888888888889,10.63111111111111,29.900000000000002 +14.833333333333334,-10.833333333333332,11.25,14.833333333333334,10.666666666666666,30.0 +14.882777777777777,-10.869444444444444,11.2875,14.882777777777777,10.702222222222222,30.1 +14.932222222222222,-10.905555555555555,11.325,14.932222222222222,10.737777777777778,30.200000000000003 +14.981666666666666,-10.941666666666666,11.362499999999999,14.981666666666666,10.773333333333333,30.3 +15.03111111111111,-10.977777777777776,11.4,15.03111111111111,10.80888888888889,30.400000000000002 +15.080555555555556,-11.013888888888888,11.4375,15.080555555555556,10.844444444444445,30.5 +15.129999999999999,-11.049999999999999,11.475,15.129999999999999,10.88,30.6 +15.179444444444444,-11.08611111111111,11.5125,15.179444444444444,10.915555555555555,30.700000000000003 +15.22888888888889,-11.122222222222222,11.549999999999999,15.22888888888889,10.95111111111111,30.8 +15.278333333333332,-11.158333333333331,11.5875,15.278333333333332,10.986666666666666,30.900000000000002 +15.327777777777778,-11.194444444444443,11.625,15.327777777777778,11.022222222222222,31.0 +15.377222222222223,-11.230555555555554,11.6625,15.377222222222223,11.057777777777778,31.1 +15.426666666666666,-11.266666666666666,11.7,15.426666666666666,11.093333333333334,31.200000000000003 +15.476111111111111,-11.302777777777777,11.737499999999999,15.476111111111111,11.12888888888889,31.3 +15.525555555555556,-11.338888888888889,11.775,15.525555555555556,11.164444444444445,31.400000000000002 +15.575,-11.374999999999998,11.8125,15.575,11.2,31.5 +15.624444444444444,-11.41111111111111,11.85,15.624444444444444,11.235555555555555,31.6 +15.67388888888889,-11.447222222222221,11.8875,15.67388888888889,11.27111111111111,31.700000000000003 +15.723333333333333,-11.483333333333333,11.924999999999999,15.723333333333333,11.306666666666667,31.8 +15.772777777777778,-11.519444444444444,11.9625,15.772777777777778,11.342222222222222,31.900000000000002 +15.822222222222223,-11.555555555555554,12.0,15.822222222222223,11.377777777777778,32.0 +15.871666666666666,-11.591666666666665,12.0375,15.871666666666666,11.413333333333334,32.1 +15.921111111111111,-11.627777777777776,12.075,15.921111111111111,11.448888888888888,32.2 +15.970555555555555,-11.663888888888888,12.112499999999999,15.970555555555555,11.484444444444444,32.300000000000004 +16.02,-11.7,12.15,16.02,11.52,32.4 +16.069444444444443,-11.73611111111111,12.1875,16.069444444444443,11.555555555555555,32.5 +16.11888888888889,-11.77222222222222,12.225,16.11888888888889,11.591111111111111,32.6 +16.168333333333333,-11.808333333333332,12.2625,16.168333333333333,11.626666666666667,32.7 +16.217777777777776,-11.844444444444443,12.299999999999999,16.217777777777776,11.662222222222223,32.800000000000004 +16.267222222222223,-11.880555555555555,12.3375,16.267222222222223,11.697777777777778,32.9 +16.316666666666666,-11.916666666666666,12.375,16.316666666666666,11.733333333333333,33.0 +16.36611111111111,-11.952777777777778,12.4125,16.36611111111111,11.768888888888888,33.1 +16.415555555555557,-11.988888888888887,12.45,16.415555555555557,11.804444444444444,33.2 +16.465,-12.024999999999999,12.487499999999999,16.465,11.84,33.300000000000004 +16.514444444444443,-12.06111111111111,12.525,16.514444444444443,11.875555555555556,33.4 +16.56388888888889,-12.097222222222221,12.5625,16.56388888888889,11.911111111111111,33.5 +16.613333333333333,-12.133333333333333,12.6,16.613333333333333,11.946666666666667,33.6 +16.662777777777777,-12.169444444444443,12.6375,16.662777777777777,11.982222222222223,33.7 +16.712222222222223,-12.205555555555554,12.674999999999999,16.712222222222223,12.017777777777777,33.800000000000004 +16.761666666666667,-12.241666666666665,12.7125,16.761666666666667,12.053333333333333,33.9 +16.81111111111111,-12.277777777777777,12.75,16.81111111111111,12.088888888888889,34.0 +16.860555555555557,-12.313888888888888,12.7875,16.860555555555557,12.124444444444444,34.1 +16.91,-12.35,12.825,16.91,12.16,34.2 +16.959444444444443,-12.38611111111111,12.862499999999999,16.959444444444443,12.195555555555556,34.300000000000004 +17.00888888888889,-12.42222222222222,12.9,17.00888888888889,12.231111111111112,34.4 +17.058333333333334,-12.458333333333332,12.9375,17.058333333333334,12.266666666666667,34.5 +17.107777777777777,-12.494444444444444,12.975,17.107777777777777,12.302222222222222,34.6 +17.157222222222224,-12.530555555555555,13.0125,17.157222222222224,12.337777777777777,34.7 +17.206666666666667,-12.566666666666665,13.049999999999999,17.206666666666667,12.373333333333333,34.800000000000004 +17.25611111111111,-12.602777777777776,13.0875,17.25611111111111,12.408888888888889,34.9 +17.305555555555554,-12.638888888888888,13.125,17.305555555555554,12.444444444444445,35.0 +17.355,-12.674999999999999,13.1625,17.355,12.48,35.1 +17.404444444444444,-12.71111111111111,13.2,17.404444444444444,12.515555555555556,35.2 +17.453888888888887,-12.747222222222222,13.237499999999999,17.453888888888887,12.55111111111111,35.300000000000004 +17.503333333333334,-12.783333333333331,13.275,17.503333333333334,12.586666666666666,35.4 +17.552777777777777,-12.819444444444443,13.3125,17.552777777777777,12.622222222222222,35.5 +17.60222222222222,-12.855555555555554,13.35,17.60222222222222,12.657777777777778,35.6 +17.651666666666667,-12.891666666666666,13.3875,17.651666666666667,12.693333333333333,35.7 +17.70111111111111,-12.927777777777777,13.424999999999999,17.70111111111111,12.72888888888889,35.800000000000004 +17.750555555555554,-12.963888888888887,13.4625,17.750555555555554,12.764444444444445,35.9 +17.8,-12.999999999999998,13.5,17.8,12.8,36.0 +17.849444444444444,-13.03611111111111,13.5375,17.849444444444444,12.835555555555555,36.1 +17.898888888888887,-13.072222222222221,13.575,17.898888888888887,12.87111111111111,36.2 +17.948333333333334,-13.108333333333333,13.612499999999999,17.948333333333334,12.906666666666666,36.300000000000004 +17.997777777777777,-13.144444444444444,13.65,17.997777777777777,12.942222222222222,36.4 +18.04722222222222,-13.180555555555554,13.6875,18.04722222222222,12.977777777777778,36.5 +18.096666666666668,-13.216666666666665,13.725,18.096666666666668,13.013333333333334,36.6 +18.14611111111111,-13.252777777777776,13.7625,18.14611111111111,13.04888888888889,36.7 +18.195555555555554,-13.288888888888888,13.799999999999999,18.195555555555554,13.084444444444445,36.800000000000004 +18.245,-13.325,13.8375,18.245,13.12,36.9 +18.294444444444444,-13.36111111111111,13.875,18.294444444444444,13.155555555555555,37.0 +18.343888888888888,-13.39722222222222,13.9125,18.343888888888888,13.19111111111111,37.1 +18.393333333333334,-13.433333333333332,13.95,18.393333333333334,13.226666666666667,37.2 +18.442777777777778,-13.469444444444443,13.987499999999999,18.442777777777778,13.262222222222222,37.300000000000004 +18.49222222222222,-13.505555555555555,14.025,18.49222222222222,13.297777777777778,37.4 +18.541666666666668,-13.541666666666666,14.0625,18.541666666666668,13.333333333333334,37.5 +18.59111111111111,-13.577777777777776,14.1,18.59111111111111,13.36888888888889,37.6 +18.640555555555554,-13.613888888888887,14.1375,18.640555555555554,13.404444444444444,37.7 +18.69,-13.649999999999999,14.174999999999999,18.69,13.44,37.800000000000004 +18.739444444444445,-13.68611111111111,14.2125,18.739444444444445,13.475555555555555,37.9 +18.788888888888888,-13.722222222222221,14.25,18.788888888888888,13.511111111111111,38.0 +18.838333333333335,-13.758333333333333,14.2875,18.838333333333335,13.546666666666667,38.1 +18.887777777777778,-13.794444444444443,14.325,18.887777777777778,13.582222222222223,38.2 +18.93722222222222,-13.830555555555554,14.362499999999999,18.93722222222222,13.617777777777778,38.300000000000004 +18.986666666666665,-13.866666666666665,14.399999999999999,18.986666666666665,13.653333333333332,38.400000000000006 +19.03611111111111,-13.902777777777777,14.4375,19.03611111111111,13.688888888888888,38.5 +19.085555555555555,-13.938888888888888,14.475,19.085555555555555,13.724444444444444,38.6 +19.134999999999998,-13.974999999999998,14.5125,19.134999999999998,13.76,38.7 +19.184444444444445,-14.01111111111111,14.549999999999999,19.184444444444445,13.795555555555556,38.800000000000004 +19.233888888888888,-14.04722222222222,14.587499999999999,19.233888888888888,13.831111111111111,38.900000000000006 +19.28333333333333,-14.083333333333332,14.625,19.28333333333333,13.866666666666667,39.0 +19.33277777777778,-14.119444444444444,14.6625,19.33277777777778,13.902222222222223,39.1 +19.38222222222222,-14.155555555555555,14.7,19.38222222222222,13.937777777777777,39.2 +19.431666666666665,-14.191666666666665,14.737499999999999,19.431666666666665,13.973333333333333,39.300000000000004 +19.48111111111111,-14.227777777777776,14.774999999999999,19.48111111111111,14.008888888888889,39.400000000000006 +19.530555555555555,-14.263888888888888,14.8125,19.530555555555555,14.044444444444444,39.5 +19.58,-14.299999999999999,14.85,19.58,14.08,39.6 +19.629444444444445,-14.33611111111111,14.8875,19.629444444444445,14.115555555555556,39.7 +19.67888888888889,-14.37222222222222,14.924999999999999,19.67888888888889,14.151111111111112,39.800000000000004 +19.72833333333333,-14.408333333333331,14.962499999999999,19.72833333333333,14.186666666666667,39.900000000000006 +19.77777777777778,-14.444444444444443,15.0,19.77777777777778,14.222222222222221,40.0 +19.827222222222222,-14.480555555555554,15.0375,19.827222222222222,14.257777777777777,40.1 +19.876666666666665,-14.516666666666666,15.075,19.876666666666665,14.293333333333333,40.2 +19.926111111111112,-14.552777777777777,15.112499999999999,19.926111111111112,14.328888888888889,40.300000000000004 +19.975555555555555,-14.588888888888887,15.149999999999999,19.975555555555555,14.364444444444445,40.400000000000006 +20.025,-14.624999999999998,15.1875,20.025,14.4,40.5 +20.074444444444445,-14.66111111111111,15.225,20.074444444444445,14.435555555555556,40.6 +20.12388888888889,-14.697222222222221,15.2625,20.12388888888889,14.471111111111112,40.7 +20.173333333333332,-14.733333333333333,15.299999999999999,20.173333333333332,14.506666666666666,40.800000000000004 +20.22277777777778,-14.769444444444444,15.337499999999999,20.22277777777778,14.542222222222222,40.900000000000006 +20.272222222222222,-14.805555555555554,15.375,20.272222222222222,14.577777777777778,41.0 +20.321666666666665,-14.841666666666665,15.4125,20.321666666666665,14.613333333333333,41.1 +20.371111111111112,-14.877777777777776,15.45,20.371111111111112,14.648888888888889,41.2 +20.420555555555556,-14.913888888888888,15.487499999999999,20.420555555555556,14.684444444444445,41.300000000000004 +20.47,-14.95,15.524999999999999,20.47,14.72,41.400000000000006 +20.519444444444446,-14.986111111111109,15.5625,20.519444444444446,14.755555555555556,41.5 +20.56888888888889,-15.02222222222222,15.6,20.56888888888889,14.79111111111111,41.6 +20.618333333333332,-15.058333333333332,15.6375,20.618333333333332,14.826666666666666,41.7 +20.66777777777778,-15.094444444444443,15.674999999999999,20.66777777777778,14.862222222222222,41.800000000000004 +20.717222222222222,-15.130555555555555,15.712499999999999,20.717222222222222,14.897777777777778,41.900000000000006 +20.766666666666666,-15.166666666666666,15.75,20.766666666666666,14.933333333333334,42.0 +20.81611111111111,-15.202777777777776,15.7875,20.81611111111111,14.96888888888889,42.1 +20.865555555555556,-15.238888888888887,15.825,20.865555555555556,15.004444444444445,42.2 +20.915,-15.274999999999999,15.862499999999999,20.915,15.04,42.300000000000004 +20.964444444444442,-15.31111111111111,15.899999999999999,20.964444444444442,15.075555555555555,42.400000000000006 +21.01388888888889,-15.347222222222221,15.9375,21.01388888888889,15.11111111111111,42.5 +21.063333333333333,-15.383333333333331,15.975,21.063333333333333,15.146666666666667,42.6 +21.112777777777776,-15.419444444444443,16.0125,21.112777777777776,15.182222222222222,42.7 +21.162222222222223,-15.455555555555554,16.05,21.162222222222223,15.217777777777778,42.800000000000004 +21.211666666666666,-15.491666666666665,16.0875,21.211666666666666,15.253333333333334,42.900000000000006 +21.26111111111111,-15.527777777777777,16.125,21.26111111111111,15.28888888888889,43.0 +21.310555555555556,-15.563888888888888,16.162499999999998,21.310555555555556,15.324444444444444,43.1 +21.36,-15.599999999999998,16.2,21.36,15.36,43.2 +21.409444444444443,-15.63611111111111,16.2375,21.409444444444443,15.395555555555555,43.300000000000004 +21.45888888888889,-15.67222222222222,16.275,21.45888888888889,15.431111111111111,43.400000000000006 +21.508333333333333,-15.708333333333332,16.3125,21.508333333333333,15.466666666666667,43.5 +21.557777777777776,-15.744444444444444,16.349999999999998,21.557777777777776,15.502222222222223,43.6 +21.607222222222223,-15.780555555555553,16.3875,21.607222222222223,15.537777777777778,43.7 +21.656666666666666,-15.816666666666665,16.425,21.656666666666666,15.573333333333334,43.800000000000004 +21.70611111111111,-15.852777777777776,16.4625,21.70611111111111,15.608888888888888,43.900000000000006 +21.755555555555556,-15.888888888888888,16.5,21.755555555555556,15.644444444444444,44.0 +21.805,-15.924999999999999,16.537499999999998,21.805,15.68,44.1 +21.854444444444443,-15.96111111111111,16.575,21.854444444444443,15.715555555555556,44.2 +21.90388888888889,-15.99722222222222,16.6125,21.90388888888889,15.751111111111111,44.300000000000004 +21.953333333333333,-16.03333333333333,16.65,21.953333333333333,15.786666666666667,44.400000000000006 +22.002777777777776,-16.069444444444443,16.6875,22.002777777777776,15.822222222222223,44.5 +22.052222222222223,-16.105555555555554,16.724999999999998,22.052222222222223,15.857777777777779,44.6 +22.101666666666667,-16.141666666666666,16.7625,22.101666666666667,15.893333333333333,44.7 +22.15111111111111,-16.177777777777777,16.8,22.15111111111111,15.928888888888888,44.800000000000004 +22.200555555555557,-16.21388888888889,16.8375,22.200555555555557,15.964444444444444,44.900000000000006 +22.25,-16.25,16.875,22.25,16.0,45.0 +22.299444444444443,-16.286111111111108,16.912499999999998,22.299444444444443,16.035555555555554,45.1 +22.34888888888889,-16.32222222222222,16.95,22.34888888888889,16.07111111111111,45.2 +22.398333333333333,-16.35833333333333,16.9875,22.398333333333333,16.106666666666666,45.300000000000004 +22.447777777777777,-16.394444444444442,17.025,22.447777777777777,16.142222222222223,45.400000000000006 +22.497222222222224,-16.430555555555554,17.0625,22.497222222222224,16.177777777777777,45.5 +22.546666666666667,-16.466666666666665,17.099999999999998,22.546666666666667,16.213333333333335,45.6 +22.59611111111111,-16.502777777777776,17.1375,22.59611111111111,16.24888888888889,45.7 +22.645555555555553,-16.538888888888888,17.175,22.645555555555553,16.284444444444443,45.800000000000004 +22.695,-16.575,17.2125,22.695,16.32,45.900000000000006 +22.744444444444444,-16.61111111111111,17.25,22.744444444444444,16.355555555555554,46.0 +22.793888888888887,-16.647222222222222,17.287499999999998,22.793888888888887,16.391111111111112,46.1 +22.843333333333334,-16.68333333333333,17.325,22.843333333333334,16.426666666666666,46.2 +22.892777777777777,-16.71944444444444,17.3625,22.892777777777777,16.462222222222223,46.300000000000004 +22.94222222222222,-16.755555555555553,17.4,22.94222222222222,16.497777777777777,46.400000000000006 +22.991666666666667,-16.791666666666664,17.4375,22.991666666666667,16.533333333333335,46.5 +23.04111111111111,-16.827777777777776,17.474999999999998,23.04111111111111,16.56888888888889,46.6 +23.090555555555554,-16.863888888888887,17.5125,23.090555555555554,16.604444444444443,46.7 +23.14,-16.9,17.55,23.14,16.64,46.800000000000004 +23.189444444444444,-16.93611111111111,17.5875,23.189444444444444,16.675555555555555,46.900000000000006 +23.238888888888887,-16.97222222222222,17.625,23.238888888888887,16.711111111111112,47.0 +23.288333333333334,-17.008333333333333,17.662499999999998,23.288333333333334,16.746666666666666,47.1 +23.337777777777777,-17.044444444444444,17.7,23.337777777777777,16.782222222222224,47.2 +23.38722222222222,-17.080555555555556,17.7375,23.38722222222222,16.817777777777778,47.300000000000004 +23.436666666666667,-17.116666666666664,17.775,23.436666666666667,16.85333333333333,47.400000000000006 +23.48611111111111,-17.152777777777775,17.8125,23.48611111111111,16.88888888888889,47.5 +23.535555555555554,-17.188888888888886,17.849999999999998,23.535555555555554,16.924444444444443,47.6 +23.585,-17.224999999999998,17.8875,23.585,16.96,47.7 +23.634444444444444,-17.26111111111111,17.925,23.634444444444444,16.995555555555555,47.800000000000004 +23.683888888888887,-17.29722222222222,17.9625,23.683888888888887,17.031111111111112,47.900000000000006 +23.733333333333334,-17.333333333333332,18.0,23.733333333333334,17.066666666666666,48.0 +23.782777777777778,-17.369444444444444,18.037499999999998,23.782777777777778,17.10222222222222,48.1 +23.83222222222222,-17.405555555555555,18.075,23.83222222222222,17.137777777777778,48.2 +23.881666666666668,-17.441666666666666,18.1125,23.881666666666668,17.173333333333332,48.300000000000004 +23.93111111111111,-17.477777777777778,18.15,23.93111111111111,17.20888888888889,48.400000000000006 +23.980555555555554,-17.513888888888886,18.1875,23.980555555555554,17.244444444444444,48.5 +24.03,-17.549999999999997,18.224999999999998,24.03,17.28,48.6 +24.079444444444444,-17.58611111111111,18.2625,24.079444444444444,17.315555555555555,48.7 +24.128888888888888,-17.62222222222222,18.3,24.128888888888888,17.351111111111113,48.800000000000004 +24.178333333333335,-17.65833333333333,18.3375,24.178333333333335,17.386666666666667,48.900000000000006 +24.227777777777778,-17.694444444444443,18.375,24.227777777777778,17.42222222222222,49.0 +24.27722222222222,-17.730555555555554,18.412499999999998,24.27722222222222,17.45777777777778,49.1 +24.326666666666668,-17.766666666666666,18.45,24.326666666666668,17.493333333333332,49.2 +24.37611111111111,-17.802777777777777,18.4875,24.37611111111111,17.52888888888889,49.300000000000004 +24.425555555555555,-17.83888888888889,18.525,24.425555555555555,17.564444444444444,49.400000000000006 +24.474999999999998,-17.875,18.5625,24.474999999999998,17.6,49.5 +24.524444444444445,-17.911111111111108,18.599999999999998,24.524444444444445,17.635555555555555,49.6 +24.573888888888888,-17.94722222222222,18.6375,24.573888888888888,17.67111111111111,49.7 +24.62333333333333,-17.98333333333333,18.675,24.62333333333333,17.706666666666667,49.800000000000004 +24.672777777777778,-18.019444444444442,18.7125,24.672777777777778,17.74222222222222,49.900000000000006 +24.72222222222222,-18.055555555555554,18.75,24.72222222222222,17.77777777777778,50.0 +24.771666666666665,-18.091666666666665,18.787499999999998,24.771666666666665,17.813333333333333,50.1 +24.82111111111111,-18.127777777777776,18.825,24.82111111111111,17.84888888888889,50.2 +24.870555555555555,-18.163888888888888,18.8625,24.870555555555555,17.884444444444444,50.300000000000004 +24.919999999999998,-18.2,18.9,24.919999999999998,17.92,50.400000000000006 +24.969444444444445,-18.23611111111111,18.9375,24.969444444444445,17.955555555555556,50.5 +25.01888888888889,-18.272222222222222,18.974999999999998,25.01888888888889,17.99111111111111,50.6 +25.06833333333333,-18.30833333333333,19.0125,25.06833333333333,18.026666666666667,50.7 +25.11777777777778,-18.34444444444444,19.05,25.11777777777778,18.06222222222222,50.800000000000004 +25.16722222222222,-18.380555555555553,19.0875,25.16722222222222,18.09777777777778,50.900000000000006 +25.216666666666665,-18.416666666666664,19.125,25.216666666666665,18.133333333333333,51.0 +25.266111111111112,-18.452777777777776,19.162499999999998,25.266111111111112,18.16888888888889,51.1 +25.315555555555555,-18.488888888888887,19.2,25.315555555555555,18.204444444444444,51.2 +25.365,-18.525,19.2375,25.365,18.24,51.300000000000004 +25.414444444444445,-18.56111111111111,19.275,25.414444444444445,18.275555555555556,51.400000000000006 +25.46388888888889,-18.59722222222222,19.3125,25.46388888888889,18.31111111111111,51.5 +25.513333333333332,-18.633333333333333,19.349999999999998,25.513333333333332,18.346666666666668,51.6 +25.56277777777778,-18.669444444444444,19.3875,25.56277777777778,18.38222222222222,51.7 +25.612222222222222,-18.705555555555552,19.425,25.612222222222222,18.41777777777778,51.800000000000004 +25.661666666666665,-18.741666666666664,19.4625,25.661666666666665,18.453333333333333,51.900000000000006 +25.711111111111112,-18.777777777777775,19.5,25.711111111111112,18.488888888888887,52.0 +25.760555555555555,-18.813888888888886,19.537499999999998,25.760555555555555,18.524444444444445,52.1 +25.81,-18.849999999999998,19.575,25.81,18.56,52.2 +25.859444444444446,-18.88611111111111,19.6125,25.859444444444446,18.595555555555556,52.300000000000004 +25.90888888888889,-18.92222222222222,19.65,25.90888888888889,18.63111111111111,52.400000000000006 +25.958333333333332,-18.958333333333332,19.6875,25.958333333333332,18.666666666666668,52.5 +26.00777777777778,-18.994444444444444,19.724999999999998,26.00777777777778,18.702222222222222,52.6 +26.057222222222222,-19.030555555555555,19.7625,26.057222222222222,18.73777777777778,52.7 +26.106666666666666,-19.066666666666666,19.8,26.106666666666666,18.773333333333333,52.800000000000004 +26.156111111111112,-19.102777777777774,19.8375,26.156111111111112,18.808888888888887,52.900000000000006 +26.205555555555556,-19.138888888888886,19.875,26.205555555555556,18.844444444444445,53.0 +26.255,-19.174999999999997,19.912499999999998,26.255,18.88,53.1 +26.304444444444442,-19.21111111111111,19.95,26.304444444444442,18.915555555555557,53.2 +26.35388888888889,-19.24722222222222,19.9875,26.35388888888889,18.95111111111111,53.300000000000004 +26.403333333333332,-19.28333333333333,20.025,26.403333333333332,18.986666666666668,53.400000000000006 +26.452777777777776,-19.319444444444443,20.0625,26.452777777777776,19.022222222222222,53.5 +26.502222222222223,-19.355555555555554,20.099999999999998,26.502222222222223,19.057777777777776,53.6 +26.551666666666666,-19.391666666666666,20.1375,26.551666666666666,19.093333333333334,53.7 +26.60111111111111,-19.427777777777777,20.175,26.60111111111111,19.128888888888888,53.800000000000004 +26.650555555555556,-19.46388888888889,20.2125,26.650555555555556,19.164444444444445,53.900000000000006 +26.7,-19.499999999999996,20.25,26.7,19.2,54.0 +26.749444444444443,-19.536111111111108,20.287499999999998,26.749444444444443,19.235555555555557,54.1 +26.79888888888889,-19.57222222222222,20.325,26.79888888888889,19.27111111111111,54.2 +26.848333333333333,-19.60833333333333,20.3625,26.848333333333333,19.30666666666667,54.300000000000004 +26.897777777777776,-19.644444444444442,20.4,26.897777777777776,19.342222222222222,54.400000000000006 +26.947222222222223,-19.680555555555554,20.4375,26.947222222222223,19.377777777777776,54.5 +26.996666666666666,-19.716666666666665,20.474999999999998,26.996666666666666,19.413333333333334,54.6 +27.04611111111111,-19.752777777777776,20.5125,27.04611111111111,19.448888888888888,54.7 +27.095555555555556,-19.788888888888888,20.55,27.095555555555556,19.484444444444446,54.800000000000004 +27.145,-19.825,20.5875,27.145,19.52,54.900000000000006 +27.194444444444443,-19.86111111111111,20.625,27.194444444444443,19.555555555555557,55.0 +27.24388888888889,-19.89722222222222,20.662499999999998,27.24388888888889,19.59111111111111,55.1 +27.293333333333333,-19.93333333333333,20.7,27.293333333333333,19.626666666666665,55.2 +27.342777777777776,-19.96944444444444,20.7375,27.342777777777776,19.662222222222223,55.300000000000004 +27.392222222222223,-20.005555555555553,20.775,27.392222222222223,19.697777777777777,55.400000000000006 +27.441666666666666,-20.041666666666664,20.8125,27.441666666666666,19.733333333333334,55.5 +27.49111111111111,-20.077777777777776,20.849999999999998,27.49111111111111,19.76888888888889,55.6 +27.540555555555557,-20.113888888888887,20.8875,27.540555555555557,19.804444444444446,55.7 +27.59,-20.15,20.925,27.59,19.84,55.800000000000004 +27.639444444444443,-20.18611111111111,20.9625,27.639444444444443,19.875555555555554,55.900000000000006 +27.68888888888889,-20.22222222222222,21.0,27.68888888888889,19.91111111111111,56.0 +27.738333333333333,-20.258333333333333,21.037499999999998,27.738333333333333,19.946666666666665,56.1 +27.787777777777777,-20.294444444444444,21.075,27.787777777777777,19.982222222222223,56.2 +27.837222222222223,-20.330555555555552,21.1125,27.837222222222223,20.017777777777777,56.300000000000004 +27.886666666666667,-20.366666666666664,21.15,27.886666666666667,20.053333333333335,56.400000000000006 +27.93611111111111,-20.402777777777775,21.1875,27.93611111111111,20.08888888888889,56.5 +27.985555555555557,-20.438888888888886,21.224999999999998,27.985555555555557,20.124444444444446,56.6 +28.035,-20.474999999999998,21.2625,28.035,20.16,56.7 +28.084444444444443,-20.51111111111111,21.3,28.084444444444443,20.195555555555554,56.800000000000004 +28.133888888888887,-20.54722222222222,21.3375,28.133888888888887,20.23111111111111,56.900000000000006 +28.183333333333334,-20.583333333333332,21.375,28.183333333333334,20.266666666666666,57.0 +28.232777777777777,-20.619444444444444,21.412499999999998,28.232777777777777,20.302222222222223,57.1 +28.28222222222222,-20.655555555555555,21.45,28.28222222222222,20.337777777777777,57.2 +28.331666666666667,-20.691666666666666,21.4875,28.331666666666667,20.373333333333335,57.300000000000004 +28.38111111111111,-20.727777777777774,21.525,28.38111111111111,20.40888888888889,57.400000000000006 +28.430555555555554,-20.763888888888886,21.5625,28.430555555555554,20.444444444444443,57.5 +28.48,-20.799999999999997,21.599999999999998,28.48,20.48,57.6 +28.529444444444444,-20.83611111111111,21.6375,28.529444444444444,20.515555555555554,57.7 +28.578888888888887,-20.87222222222222,21.675,28.578888888888887,20.551111111111112,57.800000000000004 +28.628333333333334,-20.90833333333333,21.7125,28.628333333333334,20.586666666666666,57.900000000000006 +28.677777777777777,-20.944444444444443,21.75,28.677777777777777,20.622222222222224,58.0 +28.72722222222222,-20.980555555555554,21.787499999999998,28.72722222222222,20.657777777777778,58.1 +28.776666666666667,-21.016666666666666,21.825,28.776666666666667,20.69333333333333,58.2 +28.82611111111111,-21.052777777777777,21.8625,28.82611111111111,20.72888888888889,58.300000000000004 +28.875555555555554,-21.08888888888889,21.9,28.875555555555554,20.764444444444443,58.400000000000006 +28.925,-21.124999999999996,21.9375,28.925,20.8,58.5 +28.974444444444444,-21.161111111111108,21.974999999999998,28.974444444444444,20.835555555555555,58.6 +29.023888888888887,-21.19722222222222,22.0125,29.023888888888887,20.871111111111112,58.7 +29.073333333333334,-21.23333333333333,22.05,29.073333333333334,20.906666666666666,58.800000000000004 +29.122777777777777,-21.269444444444442,22.0875,29.122777777777777,20.942222222222224,58.900000000000006 +29.17222222222222,-21.305555555555554,22.125,29.17222222222222,20.977777777777778,59.0 +29.221666666666668,-21.341666666666665,22.162499999999998,29.221666666666668,21.013333333333332,59.1 +29.27111111111111,-21.377777777777776,22.2,29.27111111111111,21.04888888888889,59.2 +29.320555555555554,-21.413888888888888,22.2375,29.320555555555554,21.084444444444443,59.300000000000004 +29.37,-21.45,22.275,29.37,21.12,59.400000000000006 +29.419444444444444,-21.48611111111111,22.3125,29.419444444444444,21.155555555555555,59.5 +29.468888888888888,-21.52222222222222,22.349999999999998,29.468888888888888,21.191111111111113,59.6 +29.518333333333334,-21.55833333333333,22.3875,29.518333333333334,21.226666666666667,59.7 +29.567777777777778,-21.59444444444444,22.425,29.567777777777778,21.26222222222222,59.800000000000004 +29.61722222222222,-21.630555555555553,22.4625,29.61722222222222,21.297777777777778,59.900000000000006 +29.666666666666668,-21.666666666666664,22.5,29.666666666666668,21.333333333333332,60.0 +29.71611111111111,-21.702777777777776,22.537499999999998,29.71611111111111,21.36888888888889,60.1 +29.765555555555554,-21.738888888888887,22.575,29.765555555555554,21.404444444444444,60.2 +29.815,-21.775,22.6125,29.815,21.44,60.300000000000004 +29.864444444444445,-21.81111111111111,22.65,29.864444444444445,21.475555555555555,60.400000000000006 +29.913888888888888,-21.84722222222222,22.6875,29.913888888888888,21.511111111111113,60.5 +29.96333333333333,-21.883333333333333,22.724999999999998,29.96333333333333,21.546666666666667,60.6 +30.012777777777778,-21.91944444444444,22.7625,30.012777777777778,21.58222222222222,60.7 +30.06222222222222,-21.955555555555552,22.8,30.06222222222222,21.61777777777778,60.800000000000004 +30.111666666666665,-21.991666666666664,22.8375,30.111666666666665,21.653333333333332,60.900000000000006 +30.16111111111111,-22.027777777777775,22.875,30.16111111111111,21.68888888888889,61.0 +30.210555555555555,-22.063888888888886,22.912499999999998,30.210555555555555,21.724444444444444,61.1 +30.259999999999998,-22.099999999999998,22.95,30.259999999999998,21.76,61.2 +30.309444444444445,-22.13611111111111,22.9875,30.309444444444445,21.795555555555556,61.300000000000004 +30.358888888888888,-22.17222222222222,23.025,30.358888888888888,21.83111111111111,61.400000000000006 +30.40833333333333,-22.208333333333332,23.0625,30.40833333333333,21.866666666666667,61.5 +30.45777777777778,-22.244444444444444,23.099999999999998,30.45777777777778,21.90222222222222,61.6 +30.50722222222222,-22.280555555555555,23.1375,30.50722222222222,21.93777777777778,61.7 +30.556666666666665,-22.316666666666663,23.175,30.556666666666665,21.973333333333333,61.800000000000004 +30.60611111111111,-22.352777777777774,23.2125,30.60611111111111,22.00888888888889,61.900000000000006 +30.655555555555555,-22.388888888888886,23.25,30.655555555555555,22.044444444444444,62.0 +30.705,-22.424999999999997,23.287499999999998,30.705,22.08,62.1 +30.754444444444445,-22.46111111111111,23.325,30.754444444444445,22.115555555555556,62.2 +30.80388888888889,-22.49722222222222,23.3625,30.80388888888889,22.15111111111111,62.300000000000004 +30.85333333333333,-22.53333333333333,23.4,30.85333333333333,22.186666666666667,62.400000000000006 +30.90277777777778,-22.569444444444443,23.4375,30.90277777777778,22.22222222222222,62.5 +30.952222222222222,-22.605555555555554,23.474999999999998,30.952222222222222,22.25777777777778,62.6 +31.001666666666665,-22.641666666666666,23.5125,31.001666666666665,22.293333333333333,62.7 +31.051111111111112,-22.677777777777777,23.55,31.051111111111112,22.32888888888889,62.800000000000004 +31.100555555555555,-22.713888888888885,23.5875,31.100555555555555,22.364444444444445,62.900000000000006 +31.15,-22.749999999999996,23.625,31.15,22.4,63.0 +31.199444444444445,-22.786111111111108,23.662499999999998,31.199444444444445,22.435555555555556,63.1 +31.24888888888889,-22.82222222222222,23.7,31.24888888888889,22.47111111111111,63.2 +31.298333333333332,-22.85833333333333,23.7375,31.298333333333332,22.506666666666668,63.300000000000004 +31.34777777777778,-22.894444444444442,23.775,31.34777777777778,22.54222222222222,63.400000000000006 +31.397222222222222,-22.930555555555554,23.8125,31.397222222222222,22.57777777777778,63.5 +31.446666666666665,-22.966666666666665,23.849999999999998,31.446666666666665,22.613333333333333,63.6 +31.496111111111112,-23.002777777777776,23.8875,31.496111111111112,22.648888888888887,63.7 +31.545555555555556,-23.038888888888888,23.925,31.545555555555556,22.684444444444445,63.800000000000004 +31.595,-23.075,23.9625,31.595,22.72,63.900000000000006 +31.644444444444446,-23.111111111111107,24.0,31.644444444444446,22.755555555555556,64.0 +31.69388888888889,-23.14722222222222,24.037499999999998,31.69388888888889,22.79111111111111,64.10000000000001 +31.743333333333332,-23.18333333333333,24.075,31.743333333333332,22.826666666666668,64.2 +31.792777777777776,-23.21944444444444,24.1125,31.792777777777776,22.862222222222222,64.3 +31.842222222222222,-23.255555555555553,24.15,31.842222222222222,22.897777777777776,64.4 +31.891666666666666,-23.291666666666664,24.1875,31.891666666666666,22.933333333333334,64.5 +31.94111111111111,-23.327777777777776,24.224999999999998,31.94111111111111,22.968888888888888,64.60000000000001 +31.990555555555556,-23.363888888888887,24.2625,31.990555555555556,23.004444444444445,64.7 +32.04,-23.4,24.3,32.04,23.04,64.8 +32.089444444444446,-23.43611111111111,24.3375,32.089444444444446,23.075555555555557,64.9 +32.138888888888886,-23.47222222222222,24.375,32.138888888888886,23.11111111111111,65.0 +32.18833333333333,-23.508333333333333,24.412499999999998,32.18833333333333,23.14666666666667,65.10000000000001 +32.23777777777778,-23.54444444444444,24.45,32.23777777777778,23.182222222222222,65.2 +32.28722222222222,-23.580555555555552,24.4875,32.28722222222222,23.217777777777776,65.3 +32.336666666666666,-23.616666666666664,24.525,32.336666666666666,23.253333333333334,65.4 +32.38611111111111,-23.652777777777775,24.5625,32.38611111111111,23.288888888888888,65.5 +32.43555555555555,-23.688888888888886,24.599999999999998,32.43555555555555,23.324444444444445,65.60000000000001 +32.485,-23.724999999999998,24.6375,32.485,23.36,65.7 +32.534444444444446,-23.76111111111111,24.675,32.534444444444446,23.395555555555557,65.8 +32.583888888888886,-23.79722222222222,24.7125,32.583888888888886,23.43111111111111,65.9 +32.63333333333333,-23.833333333333332,24.75,32.63333333333333,23.466666666666665,66.0 +32.68277777777778,-23.869444444444444,24.787499999999998,32.68277777777778,23.502222222222223,66.10000000000001 +32.73222222222222,-23.905555555555555,24.825,32.73222222222222,23.537777777777777,66.2 +32.781666666666666,-23.941666666666663,24.8625,32.781666666666666,23.573333333333334,66.3 +32.83111111111111,-23.977777777777774,24.9,32.83111111111111,23.608888888888888,66.4 +32.88055555555555,-24.013888888888886,24.9375,32.88055555555555,23.644444444444446,66.5 +32.93,-24.049999999999997,24.974999999999998,32.93,23.68,66.60000000000001 +32.97944444444445,-24.08611111111111,25.0125,32.97944444444445,23.715555555555557,66.7 +33.028888888888886,-24.12222222222222,25.05,33.028888888888886,23.75111111111111,66.8 +33.07833333333333,-24.15833333333333,25.0875,33.07833333333333,23.786666666666665,66.9 +33.12777777777778,-24.194444444444443,25.125,33.12777777777778,23.822222222222223,67.0 +33.17722222222222,-24.230555555555554,25.162499999999998,33.17722222222222,23.857777777777777,67.10000000000001 +33.22666666666667,-24.266666666666666,25.2,33.22666666666667,23.893333333333334,67.2 +33.27611111111111,-24.302777777777777,25.2375,33.27611111111111,23.92888888888889,67.3 +33.32555555555555,-24.338888888888885,25.275,33.32555555555555,23.964444444444446,67.4 +33.375,-24.374999999999996,25.3125,33.375,24.0,67.5 +33.42444444444445,-24.411111111111108,25.349999999999998,33.42444444444445,24.035555555555554,67.60000000000001 +33.47388888888889,-24.44722222222222,25.3875,33.47388888888889,24.07111111111111,67.7 +33.52333333333333,-24.48333333333333,25.425,33.52333333333333,24.106666666666666,67.8 +33.57277777777778,-24.519444444444442,25.4625,33.57277777777778,24.142222222222223,67.9 +33.62222222222222,-24.555555555555554,25.5,33.62222222222222,24.177777777777777,68.0 +33.67166666666667,-24.591666666666665,25.537499999999998,33.67166666666667,24.213333333333335,68.10000000000001 +33.721111111111114,-24.627777777777776,25.575,33.721111111111114,24.24888888888889,68.2 +33.77055555555555,-24.663888888888888,25.6125,33.77055555555555,24.284444444444443,68.3 +33.82,-24.7,25.65,33.82,24.32,68.4 +33.86944444444445,-24.736111111111107,25.6875,33.86944444444445,24.355555555555554,68.5 +33.91888888888889,-24.77222222222222,25.724999999999998,33.91888888888889,24.391111111111112,68.60000000000001 +33.968333333333334,-24.80833333333333,25.7625,33.968333333333334,24.426666666666666,68.7 +34.01777777777778,-24.84444444444444,25.8,34.01777777777778,24.462222222222223,68.8 +34.06722222222222,-24.880555555555553,25.8375,34.06722222222222,24.497777777777777,68.9 +34.11666666666667,-24.916666666666664,25.875,34.11666666666667,24.533333333333335,69.0 +34.166111111111114,-24.952777777777776,25.912499999999998,34.166111111111114,24.56888888888889,69.10000000000001 +34.215555555555554,-24.988888888888887,25.95,34.215555555555554,24.604444444444443,69.2 +34.265,-25.025,25.9875,34.265,24.64,69.3 +34.31444444444445,-25.06111111111111,26.025,34.31444444444445,24.675555555555555,69.4 +34.36388888888889,-25.09722222222222,26.0625,34.36388888888889,24.711111111111112,69.5 +34.413333333333334,-25.13333333333333,26.099999999999998,34.413333333333334,24.746666666666666,69.60000000000001 +34.462777777777774,-25.16944444444444,26.1375,34.462777777777774,24.782222222222224,69.7 +34.51222222222222,-25.205555555555552,26.175,34.51222222222222,24.817777777777778,69.8 +34.56166666666667,-25.241666666666664,26.2125,34.56166666666667,24.85333333333333,69.9 +34.61111111111111,-25.277777777777775,26.25,34.61111111111111,24.88888888888889,70.0 +34.660555555555554,-25.313888888888886,26.287499999999998,34.660555555555554,24.924444444444443,70.10000000000001 +34.71,-25.349999999999998,26.325,34.71,24.96,70.2 +34.75944444444444,-25.38611111111111,26.3625,34.75944444444444,24.995555555555555,70.3 +34.80888888888889,-25.42222222222222,26.4,34.80888888888889,25.031111111111112,70.4 +34.858333333333334,-25.458333333333332,26.4375,34.858333333333334,25.066666666666666,70.5 +34.907777777777774,-25.494444444444444,26.474999999999998,34.907777777777774,25.10222222222222,70.60000000000001 +34.95722222222222,-25.53055555555555,26.5125,34.95722222222222,25.137777777777778,70.7 +35.00666666666667,-25.566666666666663,26.55,35.00666666666667,25.173333333333332,70.8 +35.05611111111111,-25.602777777777774,26.5875,35.05611111111111,25.20888888888889,70.9 +35.105555555555554,-25.638888888888886,26.625,35.105555555555554,25.244444444444444,71.0 +35.155,-25.674999999999997,26.662499999999998,35.155,25.28,71.10000000000001 +35.20444444444444,-25.71111111111111,26.7,35.20444444444444,25.315555555555555,71.2 +35.25388888888889,-25.74722222222222,26.7375,35.25388888888889,25.351111111111113,71.3 +35.303333333333335,-25.78333333333333,26.775,35.303333333333335,25.386666666666667,71.4 +35.352777777777774,-25.819444444444443,26.8125,35.352777777777774,25.42222222222222,71.5 +35.40222222222222,-25.855555555555554,26.849999999999998,35.40222222222222,25.45777777777778,71.60000000000001 +35.45166666666667,-25.891666666666666,26.8875,35.45166666666667,25.493333333333332,71.7 +35.50111111111111,-25.927777777777774,26.925,35.50111111111111,25.52888888888889,71.8 +35.550555555555555,-25.963888888888885,26.9625,35.550555555555555,25.564444444444444,71.9 +35.6,-25.999999999999996,27.0,35.6,25.6,72.0 +35.64944444444444,-26.036111111111108,27.037499999999998,35.64944444444444,25.635555555555555,72.10000000000001 +35.69888888888889,-26.07222222222222,27.075,35.69888888888889,25.67111111111111,72.2 +35.748333333333335,-26.10833333333333,27.1125,35.748333333333335,25.706666666666667,72.3 +35.797777777777775,-26.144444444444442,27.15,35.797777777777775,25.74222222222222,72.4 +35.84722222222222,-26.180555555555554,27.1875,35.84722222222222,25.77777777777778,72.5 +35.89666666666667,-26.216666666666665,27.224999999999998,35.89666666666667,25.813333333333333,72.60000000000001 +35.94611111111111,-26.252777777777776,27.2625,35.94611111111111,25.84888888888889,72.7 +35.995555555555555,-26.288888888888888,27.3,35.995555555555555,25.884444444444444,72.8 +36.045,-26.325,27.3375,36.045,25.92,72.9 +36.09444444444444,-26.361111111111107,27.375,36.09444444444444,25.955555555555556,73.0 +36.14388888888889,-26.39722222222222,27.412499999999998,36.14388888888889,25.99111111111111,73.10000000000001 +36.193333333333335,-26.43333333333333,27.45,36.193333333333335,26.026666666666667,73.2 +36.242777777777775,-26.46944444444444,27.4875,36.242777777777775,26.06222222222222,73.3 +36.29222222222222,-26.505555555555553,27.525,36.29222222222222,26.09777777777778,73.4 +36.34166666666667,-26.541666666666664,27.5625,36.34166666666667,26.133333333333333,73.5 +36.39111111111111,-26.577777777777776,27.599999999999998,36.39111111111111,26.16888888888889,73.60000000000001 +36.440555555555555,-26.613888888888887,27.6375,36.440555555555555,26.204444444444444,73.7 +36.49,-26.65,27.675,36.49,26.24,73.8 +36.53944444444444,-26.68611111111111,27.7125,36.53944444444444,26.275555555555556,73.9 +36.58888888888889,-26.72222222222222,27.75,36.58888888888889,26.31111111111111,74.0 +36.638333333333335,-26.75833333333333,27.787499999999998,36.638333333333335,26.346666666666668,74.10000000000001 +36.687777777777775,-26.79444444444444,27.825,36.687777777777775,26.38222222222222,74.2 +36.73722222222222,-26.830555555555552,27.8625,36.73722222222222,26.41777777777778,74.3 +36.78666666666667,-26.866666666666664,27.9,36.78666666666667,26.453333333333333,74.4 +36.83611111111111,-26.902777777777775,27.9375,36.83611111111111,26.488888888888887,74.5 +36.885555555555555,-26.938888888888886,27.974999999999998,36.885555555555555,26.524444444444445,74.60000000000001 +36.935,-26.974999999999998,28.0125,36.935,26.56,74.7 +36.98444444444444,-27.01111111111111,28.05,36.98444444444444,26.595555555555556,74.8 +37.03388888888889,-27.04722222222222,28.0875,37.03388888888889,26.63111111111111,74.9 +37.083333333333336,-27.083333333333332,28.125,37.083333333333336,26.666666666666668,75.0 +37.132777777777775,-27.119444444444444,28.162499999999998,37.132777777777775,26.702222222222222,75.10000000000001 +37.18222222222222,-27.15555555555555,28.2,37.18222222222222,26.73777777777778,75.2 +37.23166666666667,-27.191666666666663,28.2375,37.23166666666667,26.773333333333333,75.3 +37.28111111111111,-27.227777777777774,28.275,37.28111111111111,26.808888888888887,75.4 +37.330555555555556,-27.263888888888886,28.3125,37.330555555555556,26.844444444444445,75.5 +37.38,-27.299999999999997,28.349999999999998,37.38,26.88,75.60000000000001 +37.42944444444444,-27.33611111111111,28.3875,37.42944444444444,26.915555555555557,75.7 +37.47888888888889,-27.37222222222222,28.425,37.47888888888889,26.95111111111111,75.8 +37.528333333333336,-27.40833333333333,28.4625,37.528333333333336,26.986666666666668,75.9 +37.577777777777776,-27.444444444444443,28.5,37.577777777777776,27.022222222222222,76.0 +37.62722222222222,-27.480555555555554,28.537499999999998,37.62722222222222,27.057777777777776,76.10000000000001 +37.67666666666667,-27.516666666666666,28.575,37.67666666666667,27.093333333333334,76.2 +37.72611111111111,-27.552777777777774,28.6125,37.72611111111111,27.128888888888888,76.3 +37.775555555555556,-27.588888888888885,28.65,37.775555555555556,27.164444444444445,76.4 +37.825,-27.624999999999996,28.6875,37.825,27.2,76.5 +37.87444444444444,-27.661111111111108,28.724999999999998,37.87444444444444,27.235555555555557,76.60000000000001 +37.92388888888889,-27.69722222222222,28.7625,37.92388888888889,27.27111111111111,76.7 +37.97333333333333,-27.73333333333333,28.799999999999997,37.97333333333333,27.306666666666665,76.80000000000001 +38.022777777777776,-27.769444444444442,28.8375,38.022777777777776,27.342222222222222,76.9 +38.07222222222222,-27.805555555555554,28.875,38.07222222222222,27.377777777777776,77.0 +38.12166666666666,-27.841666666666665,28.912499999999998,38.12166666666666,27.413333333333334,77.10000000000001 +38.17111111111111,-27.877777777777776,28.95,38.17111111111111,27.448888888888888,77.2 +38.220555555555556,-27.913888888888888,28.987499999999997,38.220555555555556,27.484444444444446,77.30000000000001 +38.269999999999996,-27.949999999999996,29.025,38.269999999999996,27.52,77.4 +38.31944444444444,-27.986111111111107,29.0625,38.31944444444444,27.555555555555557,77.5 +38.36888888888889,-28.02222222222222,29.099999999999998,38.36888888888889,27.59111111111111,77.60000000000001 +38.41833333333333,-28.05833333333333,29.1375,38.41833333333333,27.626666666666665,77.7 +38.467777777777776,-28.09444444444444,29.174999999999997,38.467777777777776,27.662222222222223,77.80000000000001 +38.51722222222222,-28.130555555555553,29.2125,38.51722222222222,27.697777777777777,77.9 +38.56666666666666,-28.166666666666664,29.25,38.56666666666666,27.733333333333334,78.0 +38.61611111111111,-28.202777777777776,29.287499999999998,38.61611111111111,27.76888888888889,78.10000000000001 +38.66555555555556,-28.238888888888887,29.325,38.66555555555556,27.804444444444446,78.2 +38.714999999999996,-28.275,29.362499999999997,38.714999999999996,27.84,78.30000000000001 +38.76444444444444,-28.31111111111111,29.4,38.76444444444444,27.875555555555554,78.4 +38.81388888888889,-28.347222222222218,29.4375,38.81388888888889,27.91111111111111,78.5 +38.86333333333333,-28.38333333333333,29.474999999999998,38.86333333333333,27.946666666666665,78.60000000000001 +38.91277777777778,-28.41944444444444,29.5125,38.91277777777778,27.982222222222223,78.7 +38.96222222222222,-28.455555555555552,29.549999999999997,38.96222222222222,28.017777777777777,78.80000000000001 +39.01166666666666,-28.491666666666664,29.5875,39.01166666666666,28.053333333333335,78.9 +39.06111111111111,-28.527777777777775,29.625,39.06111111111111,28.08888888888889,79.0 +39.11055555555556,-28.563888888888886,29.662499999999998,39.11055555555556,28.124444444444446,79.10000000000001 +39.16,-28.599999999999998,29.7,39.16,28.16,79.2 +39.20944444444444,-28.63611111111111,29.737499999999997,39.20944444444444,28.195555555555554,79.30000000000001 +39.25888888888889,-28.67222222222222,29.775,39.25888888888889,28.23111111111111,79.4 +39.30833333333333,-28.708333333333332,29.8125,39.30833333333333,28.266666666666666,79.5 +39.35777777777778,-28.74444444444444,29.849999999999998,39.35777777777778,28.302222222222223,79.60000000000001 +39.407222222222224,-28.78055555555555,29.8875,39.407222222222224,28.337777777777777,79.7 +39.45666666666666,-28.816666666666663,29.924999999999997,39.45666666666666,28.373333333333335,79.80000000000001 +39.50611111111111,-28.852777777777774,29.9625,39.50611111111111,28.40888888888889,79.9 +39.55555555555556,-28.888888888888886,30.0,39.55555555555556,28.444444444444443,80.0 +39.605,-28.924999999999997,30.037499999999998,39.605,28.48,80.10000000000001 +39.654444444444444,-28.96111111111111,30.075,39.654444444444444,28.515555555555554,80.2 +39.70388888888889,-28.99722222222222,30.112499999999997,39.70388888888889,28.551111111111112,80.30000000000001 +39.75333333333333,-29.03333333333333,30.15,39.75333333333333,28.586666666666666,80.4 +39.80277777777778,-29.069444444444443,30.1875,39.80277777777778,28.622222222222224,80.5 +39.852222222222224,-29.105555555555554,30.224999999999998,39.852222222222224,28.657777777777778,80.60000000000001 +39.901666666666664,-29.141666666666662,30.2625,39.901666666666664,28.69333333333333,80.7 +39.95111111111111,-29.177777777777774,30.299999999999997,39.95111111111111,28.72888888888889,80.80000000000001 +40.00055555555556,-29.213888888888885,30.3375,40.00055555555556,28.764444444444443,80.9 +40.05,-29.249999999999996,30.375,40.05,28.8,81.0 +40.099444444444444,-29.286111111111108,30.412499999999998,40.099444444444444,28.835555555555555,81.10000000000001 +40.14888888888889,-29.32222222222222,30.45,40.14888888888889,28.871111111111112,81.2 +40.19833333333333,-29.35833333333333,30.487499999999997,40.19833333333333,28.906666666666666,81.30000000000001 +40.24777777777778,-29.394444444444442,30.525,40.24777777777778,28.942222222222224,81.4 +40.297222222222224,-29.430555555555554,30.5625,40.297222222222224,28.977777777777778,81.5 +40.346666666666664,-29.466666666666665,30.599999999999998,40.346666666666664,29.013333333333332,81.60000000000001 +40.39611111111111,-29.502777777777776,30.6375,40.39611111111111,29.04888888888889,81.7 +40.44555555555556,-29.538888888888888,30.674999999999997,40.44555555555556,29.084444444444443,81.80000000000001 +40.495,-29.574999999999996,30.7125,40.495,29.12,81.9 +40.544444444444444,-29.611111111111107,30.75,40.544444444444444,29.155555555555555,82.0 +40.59388888888889,-29.64722222222222,30.787499999999998,40.59388888888889,29.191111111111113,82.10000000000001 +40.64333333333333,-29.68333333333333,30.825,40.64333333333333,29.226666666666667,82.2 +40.69277777777778,-29.71944444444444,30.862499999999997,40.69277777777778,29.26222222222222,82.30000000000001 +40.742222222222225,-29.755555555555553,30.9,40.742222222222225,29.297777777777778,82.4 +40.791666666666664,-29.791666666666664,30.9375,40.791666666666664,29.333333333333332,82.5 +40.84111111111111,-29.827777777777776,30.974999999999998,40.84111111111111,29.36888888888889,82.60000000000001 +40.89055555555556,-29.863888888888887,31.0125,40.89055555555556,29.404444444444444,82.7 +40.94,-29.9,31.049999999999997,40.94,29.44,82.80000000000001 +40.989444444444445,-29.93611111111111,31.0875,40.989444444444445,29.475555555555555,82.9 +41.03888888888889,-29.972222222222218,31.125,41.03888888888889,29.511111111111113,83.0 +41.08833333333333,-30.00833333333333,31.162499999999998,41.08833333333333,29.546666666666667,83.10000000000001 +41.13777777777778,-30.04444444444444,31.2,41.13777777777778,29.58222222222222,83.2 +41.187222222222225,-30.080555555555552,31.237499999999997,41.187222222222225,29.61777777777778,83.30000000000001 +41.236666666666665,-30.116666666666664,31.275,41.236666666666665,29.653333333333332,83.4 +41.28611111111111,-30.152777777777775,31.3125,41.28611111111111,29.68888888888889,83.5 +41.33555555555556,-30.188888888888886,31.349999999999998,41.33555555555556,29.724444444444444,83.60000000000001 +41.385,-30.224999999999998,31.3875,41.385,29.76,83.7 +41.434444444444445,-30.26111111111111,31.424999999999997,41.434444444444445,29.795555555555556,83.80000000000001 +41.48388888888889,-30.29722222222222,31.4625,41.48388888888889,29.83111111111111,83.9 +41.53333333333333,-30.333333333333332,31.5,41.53333333333333,29.866666666666667,84.0 +41.58277777777778,-30.36944444444444,31.537499999999998,41.58277777777778,29.90222222222222,84.10000000000001 +41.63222222222222,-30.40555555555555,31.575,41.63222222222222,29.93777777777778,84.2 +41.681666666666665,-30.441666666666663,31.612499999999997,41.681666666666665,29.973333333333333,84.30000000000001 +41.73111111111111,-30.477777777777774,31.65,41.73111111111111,30.00888888888889,84.4 +41.78055555555555,-30.513888888888886,31.6875,41.78055555555555,30.044444444444444,84.5 +41.83,-30.549999999999997,31.724999999999998,41.83,30.08,84.60000000000001 +41.879444444444445,-30.58611111111111,31.7625,41.879444444444445,30.115555555555556,84.7 +41.928888888888885,-30.62222222222222,31.799999999999997,41.928888888888885,30.15111111111111,84.80000000000001 +41.97833333333333,-30.65833333333333,31.8375,41.97833333333333,30.186666666666667,84.9 +42.02777777777778,-30.694444444444443,31.875,42.02777777777778,30.22222222222222,85.0 +42.07722222222222,-30.730555555555554,31.912499999999998,42.07722222222222,30.25777777777778,85.10000000000001 +42.126666666666665,-30.766666666666662,31.95,42.126666666666665,30.293333333333333,85.2 +42.17611111111111,-30.802777777777774,31.987499999999997,42.17611111111111,30.32888888888889,85.30000000000001 +42.22555555555555,-30.838888888888885,32.025,42.22555555555555,30.364444444444445,85.4 +42.275,-30.874999999999996,32.0625,42.275,30.4,85.5 +42.324444444444445,-30.911111111111108,32.1,42.324444444444445,30.435555555555556,85.60000000000001 +42.373888888888885,-30.94722222222222,32.137499999999996,42.373888888888885,30.47111111111111,85.7 +42.42333333333333,-30.98333333333333,32.175,42.42333333333333,30.506666666666668,85.80000000000001 +42.47277777777778,-31.019444444444442,32.2125,42.47277777777778,30.54222222222222,85.9 +42.52222222222222,-31.055555555555554,32.25,42.52222222222222,30.57777777777778,86.0 +42.571666666666665,-31.091666666666665,32.2875,42.571666666666665,30.613333333333333,86.10000000000001 +42.62111111111111,-31.127777777777776,32.324999999999996,42.62111111111111,30.648888888888887,86.2 +42.67055555555555,-31.163888888888884,32.3625,42.67055555555555,30.684444444444445,86.30000000000001 +42.72,-31.199999999999996,32.4,42.72,30.72,86.4 +42.769444444444446,-31.236111111111107,32.4375,42.769444444444446,30.755555555555556,86.5 +42.818888888888885,-31.27222222222222,32.475,42.818888888888885,30.79111111111111,86.60000000000001 +42.86833333333333,-31.30833333333333,32.512499999999996,42.86833333333333,30.826666666666668,86.7 +42.91777777777778,-31.34444444444444,32.55,42.91777777777778,30.862222222222222,86.80000000000001 +42.96722222222222,-31.380555555555553,32.5875,42.96722222222222,30.897777777777776,86.9 +43.016666666666666,-31.416666666666664,32.625,43.016666666666666,30.933333333333334,87.0 +43.06611111111111,-31.452777777777776,32.6625,43.06611111111111,30.968888888888888,87.10000000000001 +43.11555555555555,-31.488888888888887,32.699999999999996,43.11555555555555,31.004444444444445,87.2 +43.165,-31.525,32.7375,43.165,31.04,87.30000000000001 +43.214444444444446,-31.561111111111106,32.775,43.214444444444446,31.075555555555557,87.4 +43.263888888888886,-31.597222222222218,32.8125,43.263888888888886,31.11111111111111,87.5 +43.31333333333333,-31.63333333333333,32.85,43.31333333333333,31.14666666666667,87.60000000000001 +43.36277777777778,-31.66944444444444,32.887499999999996,43.36277777777778,31.182222222222222,87.7 +43.41222222222222,-31.705555555555552,32.925,43.41222222222222,31.217777777777776,87.80000000000001 +43.461666666666666,-31.741666666666664,32.9625,43.461666666666666,31.253333333333334,87.9 +43.51111111111111,-31.777777777777775,33.0,43.51111111111111,31.288888888888888,88.0 +43.56055555555555,-31.813888888888886,33.0375,43.56055555555555,31.324444444444445,88.10000000000001 +43.61,-31.849999999999998,33.074999999999996,43.61,31.36,88.2 +43.659444444444446,-31.88611111111111,33.1125,43.659444444444446,31.395555555555557,88.30000000000001 +43.708888888888886,-31.92222222222222,33.15,43.708888888888886,31.43111111111111,88.4 +43.75833333333333,-31.95833333333333,33.1875,43.75833333333333,31.466666666666665,88.5 +43.80777777777778,-31.99444444444444,33.225,43.80777777777778,31.502222222222223,88.60000000000001 +43.85722222222222,-32.03055555555555,33.262499999999996,43.85722222222222,31.537777777777777,88.7 +43.906666666666666,-32.06666666666666,33.3,43.906666666666666,31.573333333333334,88.80000000000001 +43.95611111111111,-32.102777777777774,33.3375,43.95611111111111,31.608888888888888,88.9 +44.00555555555555,-32.138888888888886,33.375,44.00555555555555,31.644444444444446,89.0 +44.055,-32.175,33.4125,44.055,31.68,89.10000000000001 +44.10444444444445,-32.21111111111111,33.449999999999996,44.10444444444445,31.715555555555557,89.2 +44.153888888888886,-32.24722222222222,33.4875,44.153888888888886,31.75111111111111,89.30000000000001 +44.20333333333333,-32.28333333333333,33.525,44.20333333333333,31.786666666666665,89.4 +44.25277777777778,-32.31944444444444,33.5625,44.25277777777778,31.822222222222223,89.5 +44.30222222222222,-32.355555555555554,33.6,44.30222222222222,31.857777777777777,89.60000000000001 +44.35166666666667,-32.391666666666666,33.637499999999996,44.35166666666667,31.893333333333334,89.7 +44.40111111111111,-32.42777777777778,33.675,44.40111111111111,31.92888888888889,89.80000000000001 +44.45055555555555,-32.46388888888889,33.7125,44.45055555555555,31.964444444444446,89.9 +44.5,-32.5,33.75,44.5,32.0,90.0 +44.54944444444445,-32.53611111111111,33.7875,44.54944444444445,32.035555555555554,90.10000000000001 +44.59888888888889,-32.572222222222216,33.824999999999996,44.59888888888889,32.07111111111111,90.2 +44.64833333333333,-32.60833333333333,33.8625,44.64833333333333,32.10666666666667,90.30000000000001 +44.69777777777778,-32.64444444444444,33.9,44.69777777777778,32.14222222222222,90.4 +44.74722222222222,-32.68055555555555,33.9375,44.74722222222222,32.17777777777778,90.5 +44.79666666666667,-32.71666666666666,33.975,44.79666666666667,32.21333333333333,90.60000000000001 +44.846111111111114,-32.75277777777777,34.012499999999996,44.846111111111114,32.24888888888889,90.7 +44.89555555555555,-32.788888888888884,34.05,44.89555555555555,32.284444444444446,90.80000000000001 +44.945,-32.824999999999996,34.0875,44.945,32.32,90.9 +44.99444444444445,-32.86111111111111,34.125,44.99444444444445,32.355555555555554,91.0 +45.04388888888889,-32.89722222222222,34.1625,45.04388888888889,32.39111111111111,91.10000000000001 +45.093333333333334,-32.93333333333333,34.199999999999996,45.093333333333334,32.42666666666667,91.2 +45.14277777777778,-32.96944444444444,34.2375,45.14277777777778,32.46222222222222,91.30000000000001 +45.19222222222222,-33.00555555555555,34.275,45.19222222222222,32.49777777777778,91.4 +45.24166666666667,-33.041666666666664,34.3125,45.24166666666667,32.53333333333333,91.5 +45.29111111111111,-33.077777777777776,34.35,45.29111111111111,32.568888888888885,91.60000000000001 +45.340555555555554,-33.11388888888889,34.387499999999996,45.340555555555554,32.60444444444445,91.7 +45.39,-33.15,34.425,45.39,32.64,91.80000000000001 +45.43944444444444,-33.18611111111111,34.4625,45.43944444444444,32.675555555555555,91.9 +45.48888888888889,-33.22222222222222,34.5,45.48888888888889,32.71111111111111,92.0 +45.538333333333334,-33.25833333333333,34.5375,45.538333333333334,32.74666666666667,92.10000000000001 +45.587777777777774,-33.294444444444444,34.574999999999996,45.587777777777774,32.782222222222224,92.2 +45.63722222222222,-33.330555555555556,34.6125,45.63722222222222,32.81777777777778,92.30000000000001 +45.68666666666667,-33.36666666666666,34.65,45.68666666666667,32.85333333333333,92.4 +45.73611111111111,-33.40277777777777,34.6875,45.73611111111111,32.888888888888886,92.5 +45.785555555555554,-33.43888888888888,34.725,45.785555555555554,32.92444444444445,92.60000000000001 +45.835,-33.474999999999994,34.762499999999996,45.835,32.96,92.7 +45.88444444444444,-33.511111111111106,34.8,45.88444444444444,32.995555555555555,92.80000000000001 +45.93388888888889,-33.54722222222222,34.8375,45.93388888888889,33.03111111111111,92.9 +45.983333333333334,-33.58333333333333,34.875,45.983333333333334,33.06666666666667,93.0 +46.032777777777774,-33.61944444444444,34.9125,46.032777777777774,33.102222222222224,93.10000000000001 +46.08222222222222,-33.65555555555555,34.949999999999996,46.08222222222222,33.13777777777778,93.2 +46.13166666666667,-33.69166666666666,34.9875,46.13166666666667,33.17333333333333,93.30000000000001 +46.18111111111111,-33.727777777777774,35.025,46.18111111111111,33.208888888888886,93.4 +46.230555555555554,-33.763888888888886,35.0625,46.230555555555554,33.24444444444445,93.5 +46.28,-33.8,35.1,46.28,33.28,93.60000000000001 +46.32944444444444,-33.83611111111111,35.137499999999996,46.32944444444444,33.315555555555555,93.7 +46.37888888888889,-33.87222222222222,35.175,46.37888888888889,33.35111111111111,93.80000000000001 +46.428333333333335,-33.90833333333333,35.2125,46.428333333333335,33.38666666666666,93.9 +46.477777777777774,-33.94444444444444,35.25,46.477777777777774,33.422222222222224,94.0 +46.52722222222222,-33.980555555555554,35.2875,46.52722222222222,33.45777777777778,94.10000000000001 +46.57666666666667,-34.016666666666666,35.324999999999996,46.57666666666667,33.49333333333333,94.2 +46.62611111111111,-34.05277777777778,35.3625,46.62611111111111,33.528888888888886,94.30000000000001 +46.675555555555555,-34.08888888888889,35.4,46.675555555555555,33.56444444444445,94.4 +46.725,-34.125,35.4375,46.725,33.6,94.5 +46.77444444444444,-34.16111111111111,35.475,46.77444444444444,33.635555555555555,94.60000000000001 +46.82388888888889,-34.197222222222216,35.512499999999996,46.82388888888889,33.67111111111111,94.7 +46.873333333333335,-34.23333333333333,35.55,46.873333333333335,33.70666666666666,94.80000000000001 +46.922777777777775,-34.26944444444444,35.5875,46.922777777777775,33.742222222222225,94.9 +46.97222222222222,-34.30555555555555,35.625,46.97222222222222,33.77777777777778,95.0 +47.02166666666667,-34.34166666666666,35.6625,47.02166666666667,33.81333333333333,95.10000000000001 +47.07111111111111,-34.37777777777777,35.699999999999996,47.07111111111111,33.84888888888889,95.2 +47.120555555555555,-34.413888888888884,35.7375,47.120555555555555,33.88444444444445,95.30000000000001 +47.17,-34.449999999999996,35.775,47.17,33.92,95.4 +47.21944444444444,-34.48611111111111,35.8125,47.21944444444444,33.955555555555556,95.5 +47.26888888888889,-34.52222222222222,35.85,47.26888888888889,33.99111111111111,95.60000000000001 +47.318333333333335,-34.55833333333333,35.887499999999996,47.318333333333335,34.026666666666664,95.7 +47.367777777777775,-34.59444444444444,35.925,47.367777777777775,34.062222222222225,95.80000000000001 +47.41722222222222,-34.63055555555555,35.9625,47.41722222222222,34.09777777777778,95.9 +47.46666666666667,-34.666666666666664,36.0,47.46666666666667,34.13333333333333,96.0 +47.51611111111111,-34.702777777777776,36.0375,47.51611111111111,34.16888888888889,96.10000000000001 +47.565555555555555,-34.73888888888889,36.074999999999996,47.565555555555555,34.20444444444444,96.2 +47.615,-34.775,36.1125,47.615,34.24,96.30000000000001 +47.66444444444444,-34.81111111111111,36.15,47.66444444444444,34.275555555555556,96.4 +47.71388888888889,-34.84722222222222,36.1875,47.71388888888889,34.31111111111111,96.5 +47.763333333333335,-34.88333333333333,36.225,47.763333333333335,34.346666666666664,96.60000000000001 +47.812777777777775,-34.919444444444444,36.262499999999996,47.812777777777775,34.382222222222225,96.7 +47.86222222222222,-34.955555555555556,36.3,47.86222222222222,34.41777777777778,96.80000000000001 +47.91166666666667,-34.99166666666666,36.3375,47.91166666666667,34.45333333333333,96.9 +47.96111111111111,-35.02777777777777,36.375,47.96111111111111,34.48888888888889,97.0 +48.010555555555555,-35.06388888888888,36.4125,48.010555555555555,34.52444444444444,97.10000000000001 +48.06,-35.099999999999994,36.449999999999996,48.06,34.56,97.2 +48.10944444444444,-35.136111111111106,36.4875,48.10944444444444,34.595555555555556,97.30000000000001 +48.15888888888889,-35.17222222222222,36.525,48.15888888888889,34.63111111111111,97.4 +48.208333333333336,-35.20833333333333,36.5625,48.208333333333336,34.666666666666664,97.5 +48.257777777777775,-35.24444444444444,36.6,48.257777777777775,34.702222222222225,97.60000000000001 +48.30722222222222,-35.28055555555555,36.637499999999996,48.30722222222222,34.73777777777778,97.7 +48.35666666666667,-35.31666666666666,36.675,48.35666666666667,34.77333333333333,97.80000000000001 +48.40611111111111,-35.352777777777774,36.7125,48.40611111111111,34.80888888888889,97.9 +48.455555555555556,-35.388888888888886,36.75,48.455555555555556,34.84444444444444,98.0 +48.505,-35.425,36.7875,48.505,34.88,98.10000000000001 +48.55444444444444,-35.46111111111111,36.824999999999996,48.55444444444444,34.91555555555556,98.2 +48.60388888888889,-35.49722222222222,36.8625,48.60388888888889,34.95111111111111,98.30000000000001 +48.653333333333336,-35.53333333333333,36.9,48.653333333333336,34.986666666666665,98.4 +48.702777777777776,-35.56944444444444,36.9375,48.702777777777776,35.022222222222226,98.5 +48.75222222222222,-35.605555555555554,36.975,48.75222222222222,35.05777777777778,98.60000000000001 +48.80166666666667,-35.641666666666666,37.012499999999996,48.80166666666667,35.093333333333334,98.7 +48.85111111111111,-35.67777777777778,37.05,48.85111111111111,35.12888888888889,98.80000000000001 +48.900555555555556,-35.71388888888889,37.0875,48.900555555555556,35.16444444444444,98.9 +48.949999999999996,-35.75,37.125,48.949999999999996,35.2,99.0 +48.99944444444444,-35.786111111111104,37.1625,48.99944444444444,35.23555555555556,99.10000000000001 +49.04888888888889,-35.822222222222216,37.199999999999996,49.04888888888889,35.27111111111111,99.2 +49.09833333333333,-35.85833333333333,37.2375,49.09833333333333,35.306666666666665,99.30000000000001 +49.147777777777776,-35.89444444444444,37.275,49.147777777777776,35.34222222222222,99.4 +49.19722222222222,-35.93055555555555,37.3125,49.19722222222222,35.37777777777778,99.5 +49.24666666666666,-35.96666666666666,37.35,49.24666666666666,35.413333333333334,99.60000000000001 +49.29611111111111,-36.00277777777777,37.387499999999996,49.29611111111111,35.44888888888889,99.7 +49.345555555555556,-36.038888888888884,37.425,49.345555555555556,35.48444444444444,99.80000000000001 +49.394999999999996,-36.074999999999996,37.4625,49.394999999999996,35.52,99.9 +49.44444444444444,-36.11111111111111,37.5,49.44444444444444,35.55555555555556,100.0 +49.49388888888889,-36.14722222222222,37.5375,49.49388888888889,35.59111111111111,100.10000000000001 +49.54333333333333,-36.18333333333333,37.574999999999996,49.54333333333333,35.626666666666665,100.2 +49.592777777777776,-36.21944444444444,37.6125,49.592777777777776,35.66222222222222,100.30000000000001 +49.64222222222222,-36.25555555555555,37.65,49.64222222222222,35.69777777777778,100.4 +49.69166666666666,-36.291666666666664,37.6875,49.69166666666666,35.733333333333334,100.5 +49.74111111111111,-36.327777777777776,37.725,49.74111111111111,35.76888888888889,100.60000000000001 +49.79055555555556,-36.36388888888889,37.762499999999996,49.79055555555556,35.80444444444444,100.7 +49.839999999999996,-36.4,37.8,49.839999999999996,35.84,100.80000000000001 +49.88944444444444,-36.43611111111111,37.8375,49.88944444444444,35.87555555555556,100.9 +49.93888888888889,-36.47222222222222,37.875,49.93888888888889,35.91111111111111,101.0 +49.98833333333333,-36.50833333333333,37.9125,49.98833333333333,35.946666666666665,101.10000000000001 +50.03777777777778,-36.544444444444444,37.949999999999996,50.03777777777778,35.98222222222222,101.2 +50.08722222222222,-36.58055555555555,37.9875,50.08722222222222,36.01777777777778,101.30000000000001 +50.13666666666666,-36.61666666666666,38.025,50.13666666666666,36.053333333333335,101.4 +50.18611111111111,-36.65277777777777,38.0625,50.18611111111111,36.08888888888889,101.5 +50.23555555555556,-36.68888888888888,38.1,50.23555555555556,36.12444444444444,101.60000000000001 +50.285,-36.724999999999994,38.137499999999996,50.285,36.16,101.7 +50.33444444444444,-36.761111111111106,38.175,50.33444444444444,36.19555555555556,101.80000000000001 +50.38388888888889,-36.79722222222222,38.2125,50.38388888888889,36.23111111111111,101.9 +50.43333333333333,-36.83333333333333,38.25,50.43333333333333,36.266666666666666,102.0 +50.48277777777778,-36.86944444444444,38.2875,50.48277777777778,36.30222222222222,102.10000000000001 +50.532222222222224,-36.90555555555555,38.324999999999996,50.532222222222224,36.33777777777778,102.2 +50.58166666666666,-36.94166666666666,38.3625,50.58166666666666,36.373333333333335,102.30000000000001 +50.63111111111111,-36.977777777777774,38.4,50.63111111111111,36.40888888888889,102.4 +50.68055555555556,-37.013888888888886,38.4375,50.68055555555556,36.44444444444444,102.5 +50.73,-37.05,38.475,50.73,36.48,102.60000000000001 +50.779444444444444,-37.08611111111111,38.512499999999996,50.779444444444444,36.51555555555556,102.7 +50.82888888888889,-37.12222222222222,38.55,50.82888888888889,36.55111111111111,102.80000000000001 +50.87833333333333,-37.15833333333333,38.5875,50.87833333333333,36.586666666666666,102.9 +50.92777777777778,-37.19444444444444,38.625,50.92777777777778,36.62222222222222,103.0 +50.977222222222224,-37.230555555555554,38.6625,50.977222222222224,36.65777777777778,103.10000000000001 +51.026666666666664,-37.266666666666666,38.699999999999996,51.026666666666664,36.693333333333335,103.2 +51.07611111111111,-37.30277777777778,38.7375,51.07611111111111,36.72888888888889,103.30000000000001 +51.12555555555556,-37.33888888888889,38.775,51.12555555555556,36.76444444444444,103.4 +51.175,-37.375,38.8125,51.175,36.8,103.5 +51.224444444444444,-37.411111111111104,38.85,51.224444444444444,36.83555555555556,103.60000000000001 +51.27388888888889,-37.447222222222216,38.887499999999996,51.27388888888889,36.87111111111111,103.7 +51.32333333333333,-37.48333333333333,38.925,51.32333333333333,36.906666666666666,103.80000000000001 +51.37277777777778,-37.51944444444444,38.9625,51.37277777777778,36.94222222222222,103.9 +51.422222222222224,-37.55555555555555,39.0,51.422222222222224,36.977777777777774,104.0 +51.471666666666664,-37.59166666666666,39.0375,51.471666666666664,37.013333333333335,104.10000000000001 +51.52111111111111,-37.62777777777777,39.074999999999996,51.52111111111111,37.04888888888889,104.2 +51.57055555555556,-37.663888888888884,39.1125,51.57055555555556,37.08444444444444,104.30000000000001 +51.62,-37.699999999999996,39.15,51.62,37.12,104.4 +51.669444444444444,-37.73611111111111,39.1875,51.669444444444444,37.15555555555556,104.5 +51.71888888888889,-37.77222222222222,39.225,51.71888888888889,37.19111111111111,104.60000000000001 +51.76833333333333,-37.80833333333333,39.262499999999996,51.76833333333333,37.22666666666667,104.7 +51.81777777777778,-37.84444444444444,39.3,51.81777777777778,37.26222222222222,104.80000000000001 +51.867222222222225,-37.88055555555555,39.3375,51.867222222222225,37.297777777777775,104.9 +51.916666666666664,-37.916666666666664,39.375,51.916666666666664,37.333333333333336,105.0 +51.96611111111111,-37.952777777777776,39.4125,51.96611111111111,37.36888888888889,105.10000000000001 +52.01555555555556,-37.98888888888889,39.449999999999996,52.01555555555556,37.404444444444444,105.2 +52.065,-38.025,39.4875,52.065,37.44,105.30000000000001 +52.114444444444445,-38.06111111111111,39.525,52.114444444444445,37.47555555555556,105.4 +52.16388888888889,-38.09722222222222,39.5625,52.16388888888889,37.51111111111111,105.5 +52.21333333333333,-38.13333333333333,39.6,52.21333333333333,37.54666666666667,105.60000000000001 +52.26277777777778,-38.169444444444444,39.637499999999996,52.26277777777778,37.58222222222222,105.7 +52.312222222222225,-38.20555555555555,39.675,52.312222222222225,37.617777777777775,105.80000000000001 +52.361666666666665,-38.24166666666666,39.7125,52.361666666666665,37.653333333333336,105.9 +52.41111111111111,-38.27777777777777,39.75,52.41111111111111,37.68888888888889,106.0 +52.46055555555555,-38.31388888888888,39.7875,52.46055555555555,37.724444444444444,106.10000000000001 +52.51,-38.349999999999994,39.824999999999996,52.51,37.76,106.2 +52.559444444444445,-38.386111111111106,39.8625,52.559444444444445,37.79555555555555,106.30000000000001 +52.608888888888885,-38.42222222222222,39.9,52.608888888888885,37.83111111111111,106.4 +52.65833333333333,-38.45833333333333,39.9375,52.65833333333333,37.86666666666667,106.5 +52.70777777777778,-38.49444444444444,39.975,52.70777777777778,37.90222222222222,106.60000000000001 +52.75722222222222,-38.53055555555555,40.012499999999996,52.75722222222222,37.937777777777775,106.7 +52.806666666666665,-38.56666666666666,40.05,52.806666666666665,37.973333333333336,106.80000000000001 +52.85611111111111,-38.602777777777774,40.0875,52.85611111111111,38.00888888888889,106.9 +52.90555555555555,-38.638888888888886,40.125,52.90555555555555,38.044444444444444,107.0 +52.955,-38.675,40.1625,52.955,38.08,107.10000000000001 +53.004444444444445,-38.71111111111111,40.199999999999996,53.004444444444445,38.11555555555555,107.2 +53.053888888888885,-38.74722222222222,40.2375,53.053888888888885,38.15111111111111,107.30000000000001 +53.10333333333333,-38.78333333333333,40.275,53.10333333333333,38.18666666666667,107.4 +53.15277777777778,-38.81944444444444,40.3125,53.15277777777778,38.22222222222222,107.5 +53.20222222222222,-38.855555555555554,40.35,53.20222222222222,38.257777777777775,107.60000000000001 +53.251666666666665,-38.891666666666666,40.387499999999996,53.251666666666665,38.29333333333334,107.7 +53.30111111111111,-38.92777777777778,40.425,53.30111111111111,38.32888888888889,107.80000000000001 +53.35055555555555,-38.96388888888889,40.4625,53.35055555555555,38.364444444444445,107.9 +53.4,-38.99999999999999,40.5,53.4,38.4,108.0 +53.449444444444445,-39.036111111111104,40.5375,53.449444444444445,38.43555555555555,108.10000000000001 +53.498888888888885,-39.072222222222216,40.574999999999996,53.498888888888885,38.471111111111114,108.2 +53.54833333333333,-39.10833333333333,40.6125,53.54833333333333,38.50666666666667,108.30000000000001 +53.59777777777778,-39.14444444444444,40.65,53.59777777777778,38.54222222222222,108.4 +53.64722222222222,-39.18055555555555,40.6875,53.64722222222222,38.577777777777776,108.5 +53.696666666666665,-39.21666666666666,40.725,53.696666666666665,38.61333333333334,108.60000000000001 +53.74611111111111,-39.25277777777777,40.762499999999996,53.74611111111111,38.64888888888889,108.7 +53.79555555555555,-39.288888888888884,40.8,53.79555555555555,38.684444444444445,108.80000000000001 +53.845,-39.324999999999996,40.8375,53.845,38.72,108.9 +53.894444444444446,-39.36111111111111,40.875,53.894444444444446,38.75555555555555,109.0 +53.943888888888885,-39.39722222222222,40.9125,53.943888888888885,38.791111111111114,109.10000000000001 +53.99333333333333,-39.43333333333333,40.949999999999996,53.99333333333333,38.82666666666667,109.2 +54.04277777777778,-39.46944444444444,40.9875,54.04277777777778,38.86222222222222,109.30000000000001 +54.09222222222222,-39.50555555555555,41.025,54.09222222222222,38.897777777777776,109.4 +54.141666666666666,-39.541666666666664,41.0625,54.141666666666666,38.93333333333333,109.5 +54.19111111111111,-39.577777777777776,41.1,54.19111111111111,38.96888888888889,109.60000000000001 +54.24055555555555,-39.61388888888889,41.137499999999996,54.24055555555555,39.004444444444445,109.7 +54.29,-39.65,41.175,54.29,39.04,109.80000000000001 +54.339444444444446,-39.68611111111111,41.2125,54.339444444444446,39.07555555555555,109.9 +54.388888888888886,-39.72222222222222,41.25,54.388888888888886,39.111111111111114,110.0 +54.43833333333333,-39.75833333333333,41.2875,54.43833333333333,39.14666666666667,110.10000000000001 +54.48777777777778,-39.79444444444444,41.324999999999996,54.48777777777778,39.18222222222222,110.2 +54.53722222222222,-39.83055555555555,41.3625,54.53722222222222,39.217777777777776,110.30000000000001 +54.586666666666666,-39.86666666666666,41.4,54.586666666666666,39.25333333333333,110.4 +54.63611111111111,-39.90277777777777,41.4375,54.63611111111111,39.28888888888889,110.5 +54.68555555555555,-39.93888888888888,41.475,54.68555555555555,39.324444444444445,110.60000000000001 +54.735,-39.974999999999994,41.512499999999996,54.735,39.36,110.7 +54.784444444444446,-40.011111111111106,41.55,54.784444444444446,39.39555555555555,110.80000000000001 +54.833888888888886,-40.04722222222222,41.5875,54.833888888888886,39.431111111111115,110.9 +54.88333333333333,-40.08333333333333,41.625,54.88333333333333,39.46666666666667,111.0 +54.93277777777778,-40.11944444444444,41.6625,54.93277777777778,39.50222222222222,111.10000000000001 +54.98222222222222,-40.15555555555555,41.699999999999996,54.98222222222222,39.53777777777778,111.2 +55.031666666666666,-40.19166666666666,41.7375,55.031666666666666,39.57333333333333,111.30000000000001 +55.08111111111111,-40.227777777777774,41.775,55.08111111111111,39.60888888888889,111.4 +55.13055555555555,-40.263888888888886,41.8125,55.13055555555555,39.644444444444446,111.5 +55.18,-40.3,41.85,55.18,39.68,111.60000000000001 +55.22944444444445,-40.33611111111111,41.887499999999996,55.22944444444445,39.715555555555554,111.7 +55.278888888888886,-40.37222222222222,41.925,55.278888888888886,39.75111111111111,111.80000000000001 +55.32833333333333,-40.40833333333333,41.9625,55.32833333333333,39.78666666666667,111.9 +55.37777777777778,-40.44444444444444,42.0,55.37777777777778,39.82222222222222,112.0 +55.42722222222222,-40.480555555555554,42.0375,55.42722222222222,39.85777777777778,112.10000000000001 +55.47666666666667,-40.516666666666666,42.074999999999996,55.47666666666667,39.89333333333333,112.2 +55.52611111111111,-40.55277777777778,42.1125,55.52611111111111,39.92888888888889,112.30000000000001 +55.57555555555555,-40.58888888888889,42.15,55.57555555555555,39.964444444444446,112.4 +55.625,-40.62499999999999,42.1875,55.625,40.0,112.5 +55.67444444444445,-40.661111111111104,42.225,55.67444444444445,40.035555555555554,112.60000000000001 +55.72388888888889,-40.697222222222216,42.262499999999996,55.72388888888889,40.07111111111111,112.7 +55.77333333333333,-40.73333333333333,42.3,55.77333333333333,40.10666666666667,112.80000000000001 +55.82277777777778,-40.76944444444444,42.3375,55.82277777777778,40.14222222222222,112.9 +55.87222222222222,-40.80555555555555,42.375,55.87222222222222,40.17777777777778,113.0 +55.92166666666667,-40.84166666666666,42.4125,55.92166666666667,40.21333333333333,113.10000000000001 +55.971111111111114,-40.87777777777777,42.449999999999996,55.971111111111114,40.24888888888889,113.2 +56.02055555555555,-40.913888888888884,42.4875,56.02055555555555,40.284444444444446,113.30000000000001 +56.07,-40.949999999999996,42.525,56.07,40.32,113.4 +56.11944444444444,-40.98611111111111,42.5625,56.11944444444444,40.355555555555554,113.5 +56.16888888888889,-41.02222222222222,42.6,56.16888888888889,40.39111111111111,113.60000000000001 +56.218333333333334,-41.05833333333333,42.637499999999996,56.218333333333334,40.42666666666667,113.7 +56.26777777777777,-41.09444444444444,42.675,56.26777777777777,40.46222222222222,113.80000000000001 +56.31722222222222,-41.13055555555555,42.7125,56.31722222222222,40.49777777777778,113.9 +56.36666666666667,-41.166666666666664,42.75,56.36666666666667,40.53333333333333,114.0 +56.41611111111111,-41.202777777777776,42.7875,56.41611111111111,40.568888888888885,114.10000000000001 +56.465555555555554,-41.23888888888889,42.824999999999996,56.465555555555554,40.60444444444445,114.2 +56.515,-41.275,42.8625,56.515,40.64,114.30000000000001 +56.56444444444444,-41.31111111111111,42.9,56.56444444444444,40.675555555555555,114.4 +56.61388888888889,-41.34722222222222,42.9375,56.61388888888889,40.71111111111111,114.5 +56.663333333333334,-41.38333333333333,42.975,56.663333333333334,40.74666666666667,114.60000000000001 +56.712777777777774,-41.41944444444444,43.012499999999996,56.712777777777774,40.782222222222224,114.7 +56.76222222222222,-41.45555555555555,43.05,56.76222222222222,40.81777777777778,114.80000000000001 +56.81166666666667,-41.49166666666666,43.0875,56.81166666666667,40.85333333333333,114.9 +56.86111111111111,-41.52777777777777,43.125,56.86111111111111,40.888888888888886,115.0 +56.910555555555554,-41.56388888888888,43.1625,56.910555555555554,40.92444444444445,115.10000000000001 +56.96,-41.599999999999994,43.199999999999996,56.96,40.96,115.2 +57.00944444444444,-41.636111111111106,43.2375,57.00944444444444,40.995555555555555,115.30000000000001 +57.05888888888889,-41.67222222222222,43.275,57.05888888888889,41.03111111111111,115.4 +57.108333333333334,-41.70833333333333,43.3125,57.108333333333334,41.06666666666667,115.5 +57.157777777777774,-41.74444444444444,43.35,57.157777777777774,41.102222222222224,115.60000000000001 +57.20722222222222,-41.78055555555555,43.387499999999996,57.20722222222222,41.13777777777778,115.7 +57.25666666666667,-41.81666666666666,43.425,57.25666666666667,41.17333333333333,115.80000000000001 +57.30611111111111,-41.852777777777774,43.4625,57.30611111111111,41.208888888888886,115.9 +57.355555555555554,-41.888888888888886,43.5,57.355555555555554,41.24444444444445,116.0 +57.405,-41.925,43.5375,57.405,41.28,116.10000000000001 +57.45444444444444,-41.96111111111111,43.574999999999996,57.45444444444444,41.315555555555555,116.2 +57.50388888888889,-41.99722222222222,43.6125,57.50388888888889,41.35111111111111,116.30000000000001 +57.553333333333335,-42.03333333333333,43.65,57.553333333333335,41.38666666666666,116.4 +57.602777777777774,-42.06944444444444,43.6875,57.602777777777774,41.422222222222224,116.5 +57.65222222222222,-42.105555555555554,43.725,57.65222222222222,41.45777777777778,116.60000000000001 +57.70166666666667,-42.141666666666666,43.762499999999996,57.70166666666667,41.49333333333333,116.7 +57.75111111111111,-42.17777777777778,43.8,57.75111111111111,41.528888888888886,116.80000000000001 +57.800555555555555,-42.21388888888888,43.8375,57.800555555555555,41.56444444444445,116.9 +57.85,-42.24999999999999,43.875,57.85,41.6,117.0 +57.89944444444444,-42.286111111111104,43.9125,57.89944444444444,41.635555555555555,117.10000000000001 +57.94888888888889,-42.322222222222216,43.949999999999996,57.94888888888889,41.67111111111111,117.2 +57.998333333333335,-42.35833333333333,43.9875,57.998333333333335,41.70666666666666,117.30000000000001 +58.047777777777775,-42.39444444444444,44.025,58.047777777777775,41.742222222222225,117.4 +58.09722222222222,-42.43055555555555,44.0625,58.09722222222222,41.77777777777778,117.5 +58.14666666666667,-42.46666666666666,44.1,58.14666666666667,41.81333333333333,117.60000000000001 +58.19611111111111,-42.50277777777777,44.137499999999996,58.19611111111111,41.84888888888889,117.7 +58.245555555555555,-42.538888888888884,44.175,58.245555555555555,41.88444444444445,117.80000000000001 +58.295,-42.574999999999996,44.2125,58.295,41.92,117.9 +58.34444444444444,-42.61111111111111,44.25,58.34444444444444,41.955555555555556,118.0 +58.39388888888889,-42.64722222222222,44.2875,58.39388888888889,41.99111111111111,118.10000000000001 +58.443333333333335,-42.68333333333333,44.324999999999996,58.443333333333335,42.026666666666664,118.2 +58.492777777777775,-42.71944444444444,44.3625,58.492777777777775,42.062222222222225,118.30000000000001 +58.54222222222222,-42.75555555555555,44.4,58.54222222222222,42.09777777777778,118.4 +58.59166666666667,-42.791666666666664,44.4375,58.59166666666667,42.13333333333333,118.5 +58.64111111111111,-42.827777777777776,44.475,58.64111111111111,42.16888888888889,118.60000000000001 +58.690555555555555,-42.86388888888889,44.512499999999996,58.690555555555555,42.20444444444444,118.7 +58.74,-42.9,44.55,58.74,42.24,118.80000000000001 +58.78944444444444,-42.93611111111111,44.5875,58.78944444444444,42.275555555555556,118.9 +58.83888888888889,-42.97222222222222,44.625,58.83888888888889,42.31111111111111,119.0 +58.888333333333335,-43.008333333333326,44.6625,58.888333333333335,42.346666666666664,119.10000000000001 +58.937777777777775,-43.04444444444444,44.699999999999996,58.937777777777775,42.382222222222225,119.2 +58.98722222222222,-43.08055555555555,44.7375,58.98722222222222,42.41777777777778,119.30000000000001 +59.03666666666667,-43.11666666666666,44.775,59.03666666666667,42.45333333333333,119.4 +59.08611111111111,-43.15277777777777,44.8125,59.08611111111111,42.48888888888889,119.5 +59.135555555555555,-43.18888888888888,44.85,59.135555555555555,42.52444444444444,119.60000000000001 +59.185,-43.224999999999994,44.887499999999996,59.185,42.56,119.7 +59.23444444444444,-43.261111111111106,44.925,59.23444444444444,42.595555555555556,119.80000000000001 +59.28388888888889,-43.29722222222222,44.9625,59.28388888888889,42.63111111111111,119.9 +59.333333333333336,-43.33333333333333,45.0,59.333333333333336,42.666666666666664,120.0 +59.382777777777775,-43.36944444444444,45.0375,59.382777777777775,42.702222222222225,120.10000000000001 +59.43222222222222,-43.40555555555555,45.074999999999996,59.43222222222222,42.73777777777778,120.2 +59.48166666666667,-43.44166666666666,45.1125,59.48166666666667,42.77333333333333,120.30000000000001 +59.53111111111111,-43.477777777777774,45.15,59.53111111111111,42.80888888888889,120.4 +59.580555555555556,-43.513888888888886,45.1875,59.580555555555556,42.84444444444444,120.5 +59.63,-43.55,45.225,59.63,42.88,120.60000000000001 +59.67944444444444,-43.58611111111111,45.262499999999996,59.67944444444444,42.91555555555556,120.7 +59.72888888888889,-43.62222222222222,45.3,59.72888888888889,42.95111111111111,120.80000000000001 +59.77833333333333,-43.65833333333333,45.3375,59.77833333333333,42.986666666666665,120.9 +59.827777777777776,-43.69444444444444,45.375,59.827777777777776,43.022222222222226,121.0 +59.87722222222222,-43.730555555555554,45.4125,59.87722222222222,43.05777777777778,121.10000000000001 +59.92666666666666,-43.766666666666666,45.449999999999996,59.92666666666666,43.093333333333334,121.2 +59.97611111111111,-43.80277777777778,45.4875,59.97611111111111,43.12888888888889,121.30000000000001 +60.025555555555556,-43.83888888888888,45.525,60.025555555555556,43.16444444444444,121.4 +60.074999999999996,-43.87499999999999,45.5625,60.074999999999996,43.2,121.5 +60.12444444444444,-43.911111111111104,45.6,60.12444444444444,43.23555555555556,121.60000000000001 +60.17388888888889,-43.947222222222216,45.637499999999996,60.17388888888889,43.27111111111111,121.7 +60.22333333333333,-43.98333333333333,45.675,60.22333333333333,43.306666666666665,121.80000000000001 +60.272777777777776,-44.01944444444444,45.7125,60.272777777777776,43.34222222222222,121.9 +60.32222222222222,-44.05555555555555,45.75,60.32222222222222,43.37777777777778,122.0 +60.37166666666666,-44.09166666666666,45.7875,60.37166666666666,43.413333333333334,122.10000000000001 +60.42111111111111,-44.12777777777777,45.824999999999996,60.42111111111111,43.44888888888889,122.2 +60.470555555555556,-44.163888888888884,45.8625,60.470555555555556,43.48444444444444,122.30000000000001 +60.519999999999996,-44.199999999999996,45.9,60.519999999999996,43.52,122.4 +60.56944444444444,-44.23611111111111,45.9375,60.56944444444444,43.55555555555556,122.5 +60.61888888888889,-44.27222222222222,45.975,60.61888888888889,43.59111111111111,122.60000000000001 +60.66833333333333,-44.30833333333333,46.012499999999996,60.66833333333333,43.626666666666665,122.7 +60.717777777777776,-44.34444444444444,46.05,60.717777777777776,43.66222222222222,122.80000000000001 +60.76722222222222,-44.38055555555555,46.0875,60.76722222222222,43.69777777777778,122.9 +60.81666666666666,-44.416666666666664,46.125,60.81666666666666,43.733333333333334,123.0 +60.86611111111111,-44.452777777777776,46.1625,60.86611111111111,43.76888888888889,123.10000000000001 +60.91555555555556,-44.48888888888889,46.199999999999996,60.91555555555556,43.80444444444444,123.2 +60.964999999999996,-44.525,46.2375,60.964999999999996,43.84,123.30000000000001 +61.01444444444444,-44.56111111111111,46.275,61.01444444444444,43.87555555555556,123.4 +61.06388888888889,-44.59722222222222,46.3125,61.06388888888889,43.91111111111111,123.5 +61.11333333333333,-44.633333333333326,46.35,61.11333333333333,43.946666666666665,123.60000000000001 +61.16277777777778,-44.66944444444444,46.387499999999996,61.16277777777778,43.98222222222222,123.7 +61.21222222222222,-44.70555555555555,46.425,61.21222222222222,44.01777777777778,123.80000000000001 +61.26166666666666,-44.74166666666666,46.4625,61.26166666666666,44.053333333333335,123.9 +61.31111111111111,-44.77777777777777,46.5,61.31111111111111,44.08888888888889,124.0 +61.36055555555556,-44.81388888888888,46.5375,61.36055555555556,44.12444444444444,124.10000000000001 +61.41,-44.849999999999994,46.574999999999996,61.41,44.16,124.2 +61.45944444444444,-44.886111111111106,46.6125,61.45944444444444,44.19555555555556,124.30000000000001 +61.50888888888889,-44.92222222222222,46.65,61.50888888888889,44.23111111111111,124.4 +61.55833333333333,-44.95833333333333,46.6875,61.55833333333333,44.266666666666666,124.5 +61.60777777777778,-44.99444444444444,46.725,61.60777777777778,44.30222222222222,124.60000000000001 +61.657222222222224,-45.03055555555555,46.762499999999996,61.657222222222224,44.33777777777778,124.7 +61.70666666666666,-45.06666666666666,46.8,61.70666666666666,44.373333333333335,124.80000000000001 +61.75611111111111,-45.102777777777774,46.8375,61.75611111111111,44.40888888888889,124.9 +61.80555555555556,-45.138888888888886,46.875,61.80555555555556,44.44444444444444,125.0 +61.855,-45.175,46.9125,61.855,44.48,125.10000000000001 +61.904444444444444,-45.21111111111111,46.949999999999996,61.904444444444444,44.51555555555556,125.2 +61.95388888888889,-45.24722222222222,46.9875,61.95388888888889,44.55111111111111,125.30000000000001 +62.00333333333333,-45.28333333333333,47.025,62.00333333333333,44.586666666666666,125.4 +62.05277777777778,-45.31944444444444,47.0625,62.05277777777778,44.62222222222222,125.5 +62.102222222222224,-45.355555555555554,47.1,62.102222222222224,44.65777777777778,125.60000000000001 +62.151666666666664,-45.391666666666666,47.137499999999996,62.151666666666664,44.693333333333335,125.7 +62.20111111111111,-45.42777777777777,47.175,62.20111111111111,44.72888888888889,125.80000000000001 +62.25055555555556,-45.46388888888888,47.2125,62.25055555555556,44.76444444444444,125.9 +62.3,-45.49999999999999,47.25,62.3,44.8,126.0 +62.349444444444444,-45.536111111111104,47.2875,62.349444444444444,44.83555555555556,126.10000000000001 +62.39888888888889,-45.572222222222216,47.324999999999996,62.39888888888889,44.87111111111111,126.2 +62.44833333333333,-45.60833333333333,47.3625,62.44833333333333,44.906666666666666,126.30000000000001 +62.49777777777778,-45.64444444444444,47.4,62.49777777777778,44.94222222222222,126.4 +62.547222222222224,-45.68055555555555,47.4375,62.547222222222224,44.977777777777774,126.5 +62.596666666666664,-45.71666666666666,47.475,62.596666666666664,45.013333333333335,126.60000000000001 +62.64611111111111,-45.75277777777777,47.512499999999996,62.64611111111111,45.04888888888889,126.7 +62.69555555555556,-45.788888888888884,47.55,62.69555555555556,45.08444444444444,126.80000000000001 +62.745,-45.824999999999996,47.5875,62.745,45.12,126.9 +62.794444444444444,-45.86111111111111,47.625,62.794444444444444,45.15555555555556,127.0 +62.84388888888889,-45.89722222222222,47.6625,62.84388888888889,45.19111111111111,127.10000000000001 +62.89333333333333,-45.93333333333333,47.699999999999996,62.89333333333333,45.22666666666667,127.2 +62.94277777777778,-45.96944444444444,47.7375,62.94277777777778,45.26222222222222,127.30000000000001 +62.992222222222225,-46.00555555555555,47.775,62.992222222222225,45.297777777777775,127.4 +63.041666666666664,-46.041666666666664,47.8125,63.041666666666664,45.333333333333336,127.5 +63.09111111111111,-46.077777777777776,47.85,63.09111111111111,45.36888888888889,127.60000000000001 +63.14055555555556,-46.11388888888889,47.887499999999996,63.14055555555556,45.404444444444444,127.7 +63.19,-46.15,47.925,63.19,45.44,127.80000000000001 +63.239444444444445,-46.18611111111111,47.9625,63.239444444444445,45.47555555555556,127.9 +63.28888888888889,-46.222222222222214,48.0,63.28888888888889,45.51111111111111,128.0 +63.33833333333333,-46.258333333333326,48.0375,63.33833333333333,45.54666666666667,128.1 +63.38777777777778,-46.29444444444444,48.074999999999996,63.38777777777778,45.58222222222222,128.20000000000002 +63.43722222222222,-46.33055555555555,48.1125,63.43722222222222,45.617777777777775,128.3 +63.486666666666665,-46.36666666666666,48.15,63.486666666666665,45.653333333333336,128.4 +63.53611111111111,-46.40277777777777,48.1875,63.53611111111111,45.68888888888889,128.5 +63.58555555555555,-46.43888888888888,48.225,63.58555555555555,45.724444444444444,128.6 +63.635,-46.474999999999994,48.262499999999996,63.635,45.76,128.70000000000002 +63.684444444444445,-46.511111111111106,48.3,63.684444444444445,45.79555555555555,128.8 +63.733888888888885,-46.54722222222222,48.3375,63.733888888888885,45.83111111111111,128.9 +63.78333333333333,-46.58333333333333,48.375,63.78333333333333,45.86666666666667,129.0 +63.83277777777778,-46.61944444444444,48.4125,63.83277777777778,45.90222222222222,129.1 +63.88222222222222,-46.65555555555555,48.449999999999996,63.88222222222222,45.937777777777775,129.20000000000002 +63.931666666666665,-46.69166666666666,48.4875,63.931666666666665,45.973333333333336,129.3 +63.98111111111111,-46.727777777777774,48.525,63.98111111111111,46.00888888888889,129.4 +64.03055555555555,-46.763888888888886,48.5625,64.03055555555555,46.044444444444444,129.5 +64.08,-46.8,48.6,64.08,46.08,129.6 +64.12944444444445,-46.83611111111111,48.637499999999996,64.12944444444445,46.11555555555555,129.70000000000002 +64.17888888888889,-46.87222222222222,48.675,64.17888888888889,46.15111111111111,129.8 +64.22833333333334,-46.90833333333333,48.7125,64.22833333333334,46.18666666666667,129.9 +64.27777777777777,-46.94444444444444,48.75,64.27777777777777,46.22222222222222,130.0 +64.32722222222222,-46.980555555555554,48.7875,64.32722222222222,46.257777777777775,130.1 +64.37666666666667,-47.016666666666666,48.824999999999996,64.37666666666667,46.29333333333334,130.20000000000002 +64.42611111111111,-47.05277777777777,48.8625,64.42611111111111,46.32888888888889,130.3 +64.47555555555556,-47.08888888888888,48.9,64.47555555555556,46.364444444444445,130.4 +64.525,-47.12499999999999,48.9375,64.525,46.4,130.5 +64.57444444444444,-47.161111111111104,48.975,64.57444444444444,46.43555555555555,130.6 +64.62388888888889,-47.197222222222216,49.012499999999996,64.62388888888889,46.471111111111114,130.70000000000002 +64.67333333333333,-47.23333333333333,49.05,64.67333333333333,46.50666666666667,130.8 +64.72277777777778,-47.26944444444444,49.0875,64.72277777777778,46.54222222222222,130.9 +64.77222222222223,-47.30555555555555,49.125,64.77222222222223,46.577777777777776,131.0 +64.82166666666667,-47.34166666666666,49.1625,64.82166666666667,46.61333333333334,131.1 +64.8711111111111,-47.37777777777777,49.199999999999996,64.8711111111111,46.64888888888889,131.20000000000002 +64.92055555555555,-47.413888888888884,49.2375,64.92055555555555,46.684444444444445,131.3 +64.97,-47.449999999999996,49.275,64.97,46.72,131.4 +65.01944444444445,-47.48611111111111,49.3125,65.01944444444445,46.75555555555555,131.5 +65.06888888888889,-47.52222222222222,49.35,65.06888888888889,46.791111111111114,131.6 +65.11833333333333,-47.55833333333333,49.387499999999996,65.11833333333333,46.82666666666667,131.70000000000002 +65.16777777777777,-47.59444444444444,49.425,65.16777777777777,46.86222222222222,131.8 +65.21722222222222,-47.63055555555555,49.4625,65.21722222222222,46.897777777777776,131.9 +65.26666666666667,-47.666666666666664,49.5,65.26666666666667,46.93333333333333,132.0 +65.31611111111111,-47.702777777777776,49.5375,65.31611111111111,46.96888888888889,132.1 +65.36555555555556,-47.73888888888889,49.574999999999996,65.36555555555556,47.004444444444445,132.20000000000002 +65.41499999999999,-47.775,49.6125,65.41499999999999,47.04,132.3 +65.46444444444444,-47.81111111111111,49.65,65.46444444444444,47.07555555555555,132.4 +65.51388888888889,-47.847222222222214,49.6875,65.51388888888889,47.111111111111114,132.5 +65.56333333333333,-47.883333333333326,49.725,65.56333333333333,47.14666666666667,132.6 +65.61277777777778,-47.91944444444444,49.762499999999996,65.61277777777778,47.18222222222222,132.70000000000002 +65.66222222222223,-47.95555555555555,49.8,65.66222222222223,47.217777777777776,132.8 +65.71166666666666,-47.99166666666666,49.8375,65.71166666666666,47.25333333333333,132.9 +65.7611111111111,-48.02777777777777,49.875,65.7611111111111,47.28888888888889,133.0 +65.81055555555555,-48.06388888888888,49.9125,65.81055555555555,47.324444444444445,133.1 +65.86,-48.099999999999994,49.949999999999996,65.86,47.36,133.20000000000002 +65.90944444444445,-48.136111111111106,49.9875,65.90944444444445,47.39555555555555,133.3 +65.9588888888889,-48.17222222222222,50.025,65.9588888888889,47.431111111111115,133.4 +66.00833333333333,-48.20833333333333,50.0625,66.00833333333333,47.46666666666667,133.5 +66.05777777777777,-48.24444444444444,50.1,66.05777777777777,47.50222222222222,133.6 +66.10722222222222,-48.28055555555555,50.137499999999996,66.10722222222222,47.53777777777778,133.70000000000002 +66.15666666666667,-48.31666666666666,50.175,66.15666666666667,47.57333333333333,133.8 +66.20611111111111,-48.352777777777774,50.2125,66.20611111111111,47.60888888888889,133.9 +66.25555555555556,-48.388888888888886,50.25,66.25555555555556,47.644444444444446,134.0 +66.30499999999999,-48.425,50.2875,66.30499999999999,47.68,134.1 +66.35444444444444,-48.46111111111111,50.324999999999996,66.35444444444444,47.715555555555554,134.20000000000002 +66.40388888888889,-48.49722222222222,50.3625,66.40388888888889,47.75111111111111,134.3 +66.45333333333333,-48.53333333333333,50.4,66.45333333333333,47.78666666666667,134.4 +66.50277777777778,-48.56944444444444,50.4375,66.50277777777778,47.82222222222222,134.5 +66.55222222222223,-48.605555555555554,50.475,66.55222222222223,47.85777777777778,134.6 +66.60166666666666,-48.64166666666666,50.512499999999996,66.60166666666666,47.89333333333333,134.70000000000002 +66.6511111111111,-48.67777777777777,50.55,66.6511111111111,47.92888888888889,134.8 +66.70055555555555,-48.71388888888888,50.5875,66.70055555555555,47.964444444444446,134.9 +66.75,-48.74999999999999,50.625,66.75,48.0,135.0 +66.79944444444445,-48.786111111111104,50.6625,66.79944444444445,48.035555555555554,135.1 +66.8488888888889,-48.822222222222216,50.699999999999996,66.8488888888889,48.07111111111111,135.20000000000002 +66.89833333333333,-48.85833333333333,50.7375,66.89833333333333,48.10666666666667,135.3 +66.94777777777777,-48.89444444444444,50.775,66.94777777777777,48.14222222222222,135.4 +66.99722222222222,-48.93055555555555,50.8125,66.99722222222222,48.17777777777778,135.5 +67.04666666666667,-48.96666666666666,50.85,67.04666666666667,48.21333333333333,135.6 +67.09611111111111,-49.00277777777777,50.887499999999996,67.09611111111111,48.24888888888889,135.70000000000002 +67.14555555555556,-49.038888888888884,50.925,67.14555555555556,48.284444444444446,135.8 +67.195,-49.074999999999996,50.9625,67.195,48.32,135.9 +67.24444444444444,-49.11111111111111,51.0,67.24444444444444,48.355555555555554,136.0 +67.29388888888889,-49.14722222222222,51.0375,67.29388888888889,48.39111111111111,136.1 +67.34333333333333,-49.18333333333333,51.074999999999996,67.34333333333333,48.42666666666667,136.20000000000002 +67.39277777777778,-49.21944444444444,51.1125,67.39277777777778,48.46222222222222,136.3 +67.44222222222223,-49.25555555555555,51.15,67.44222222222223,48.49777777777778,136.4 +67.49166666666666,-49.291666666666664,51.1875,67.49166666666666,48.53333333333333,136.5 +67.5411111111111,-49.327777777777776,51.225,67.5411111111111,48.568888888888885,136.6 +67.59055555555555,-49.36388888888889,51.262499999999996,67.59055555555555,48.60444444444445,136.70000000000002 +67.64,-49.4,51.3,67.64,48.64,136.8 +67.68944444444445,-49.43611111111111,51.3375,67.68944444444445,48.675555555555555,136.9 +67.7388888888889,-49.472222222222214,51.375,67.7388888888889,48.71111111111111,137.0 +67.78833333333333,-49.508333333333326,51.4125,67.78833333333333,48.74666666666667,137.1 +67.83777777777777,-49.54444444444444,51.449999999999996,67.83777777777777,48.782222222222224,137.20000000000002 +67.88722222222222,-49.58055555555555,51.4875,67.88722222222222,48.81777777777778,137.3 +67.93666666666667,-49.61666666666666,51.525,67.93666666666667,48.85333333333333,137.4 +67.98611111111111,-49.65277777777777,51.5625,67.98611111111111,48.888888888888886,137.5 +68.03555555555556,-49.68888888888888,51.6,68.03555555555556,48.92444444444445,137.6 +68.085,-49.724999999999994,51.637499999999996,68.085,48.96,137.70000000000002 +68.13444444444444,-49.761111111111106,51.675,68.13444444444444,48.995555555555555,137.8 +68.18388888888889,-49.79722222222222,51.7125,68.18388888888889,49.03111111111111,137.9 +68.23333333333333,-49.83333333333333,51.75,68.23333333333333,49.06666666666667,138.0 +68.28277777777778,-49.86944444444444,51.7875,68.28277777777778,49.102222222222224,138.1 +68.33222222222223,-49.90555555555555,51.824999999999996,68.33222222222223,49.13777777777778,138.20000000000002 +68.38166666666666,-49.94166666666666,51.8625,68.38166666666666,49.17333333333333,138.3 +68.43111111111111,-49.977777777777774,51.9,68.43111111111111,49.208888888888886,138.4 +68.48055555555555,-50.013888888888886,51.9375,68.48055555555555,49.24444444444445,138.5 +68.53,-50.05,51.975,68.53,49.28,138.6 +68.57944444444445,-50.08611111111111,52.012499999999996,68.57944444444445,49.315555555555555,138.70000000000002 +68.6288888888889,-50.12222222222222,52.05,68.6288888888889,49.35111111111111,138.8 +68.67833333333333,-50.15833333333333,52.0875,68.67833333333333,49.38666666666666,138.9 +68.72777777777777,-50.19444444444444,52.125,68.72777777777777,49.422222222222224,139.0 +68.77722222222222,-50.230555555555554,52.1625,68.77722222222222,49.45777777777778,139.1 +68.82666666666667,-50.26666666666666,52.199999999999996,68.82666666666667,49.49333333333333,139.20000000000002 +68.87611111111111,-50.30277777777777,52.2375,68.87611111111111,49.528888888888886,139.3 +68.92555555555555,-50.33888888888888,52.275,68.92555555555555,49.56444444444445,139.4 +68.975,-50.37499999999999,52.3125,68.975,49.6,139.5 +69.02444444444444,-50.411111111111104,52.35,69.02444444444444,49.635555555555555,139.6 +69.07388888888889,-50.447222222222216,52.387499999999996,69.07388888888889,49.67111111111111,139.70000000000002 +69.12333333333333,-50.48333333333333,52.425,69.12333333333333,49.70666666666666,139.8 +69.17277777777778,-50.51944444444444,52.4625,69.17277777777778,49.742222222222225,139.9 +69.22222222222221,-50.55555555555555,52.5,69.22222222222221,49.77777777777778,140.0 +69.27166666666666,-50.59166666666666,52.5375,69.27166666666666,49.81333333333333,140.1 +69.32111111111111,-50.62777777777777,52.574999999999996,69.32111111111111,49.84888888888889,140.20000000000002 +69.37055555555555,-50.663888888888884,52.6125,69.37055555555555,49.88444444444445,140.3 +69.42,-50.699999999999996,52.65,69.42,49.92,140.4 +69.46944444444445,-50.73611111111111,52.6875,69.46944444444445,49.955555555555556,140.5 +69.51888888888888,-50.77222222222222,52.725,69.51888888888888,49.99111111111111,140.6 +69.56833333333333,-50.80833333333333,52.762499999999996,69.56833333333333,50.026666666666664,140.70000000000002 +69.61777777777777,-50.84444444444444,52.8,69.61777777777777,50.062222222222225,140.8 +69.66722222222222,-50.88055555555555,52.8375,69.66722222222222,50.09777777777778,140.9 +69.71666666666667,-50.916666666666664,52.875,69.71666666666667,50.13333333333333,141.0 +69.76611111111112,-50.952777777777776,52.9125,69.76611111111112,50.16888888888889,141.1 +69.81555555555555,-50.98888888888889,52.949999999999996,69.81555555555555,50.20444444444444,141.20000000000002 +69.865,-51.025,52.9875,69.865,50.24,141.3 +69.91444444444444,-51.0611111111111,53.025,69.91444444444444,50.275555555555556,141.4 +69.96388888888889,-51.097222222222214,53.0625,69.96388888888889,50.31111111111111,141.5 +70.01333333333334,-51.133333333333326,53.1,70.01333333333334,50.346666666666664,141.6 +70.06277777777778,-51.16944444444444,53.137499999999996,70.06277777777778,50.382222222222225,141.70000000000002 +70.11222222222221,-51.20555555555555,53.175,70.11222222222221,50.41777777777778,141.8 +70.16166666666666,-51.24166666666666,53.2125,70.16166666666666,50.45333333333333,141.9 +70.21111111111111,-51.27777777777777,53.25,70.21111111111111,50.48888888888889,142.0 +70.26055555555556,-51.31388888888888,53.2875,70.26055555555556,50.52444444444444,142.1 +70.31,-51.349999999999994,53.324999999999996,70.31,50.56,142.20000000000002 +70.35944444444445,-51.386111111111106,53.3625,70.35944444444445,50.595555555555556,142.3 +70.40888888888888,-51.42222222222222,53.4,70.40888888888888,50.63111111111111,142.4 +70.45833333333333,-51.45833333333333,53.4375,70.45833333333333,50.666666666666664,142.5 +70.50777777777778,-51.49444444444444,53.475,70.50777777777778,50.702222222222225,142.6 +70.55722222222222,-51.53055555555555,53.512499999999996,70.55722222222222,50.73777777777778,142.70000000000002 +70.60666666666667,-51.56666666666666,53.55,70.60666666666667,50.77333333333333,142.8 +70.65611111111112,-51.602777777777774,53.5875,70.65611111111112,50.80888888888889,142.9 +70.70555555555555,-51.638888888888886,53.625,70.70555555555555,50.84444444444444,143.0 +70.755,-51.675,53.6625,70.755,50.88,143.1 +70.80444444444444,-51.71111111111111,53.699999999999996,70.80444444444444,50.91555555555556,143.20000000000002 +70.85388888888889,-51.74722222222222,53.7375,70.85388888888889,50.95111111111111,143.3 +70.90333333333334,-51.78333333333333,53.775,70.90333333333334,50.986666666666665,143.4 +70.95277777777778,-51.81944444444444,53.8125,70.95277777777778,51.022222222222226,143.5 +71.00222222222222,-51.85555555555555,53.85,71.00222222222222,51.05777777777778,143.6 +71.05166666666666,-51.89166666666666,53.887499999999996,71.05166666666666,51.093333333333334,143.70000000000002 +71.10111111111111,-51.92777777777777,53.925,71.10111111111111,51.12888888888889,143.8 +71.15055555555556,-51.96388888888888,53.9625,71.15055555555556,51.16444444444444,143.9 +71.2,-51.99999999999999,54.0,71.2,51.2,144.0 +71.24944444444445,-52.036111111111104,54.0375,71.24944444444445,51.23555555555556,144.1 +71.29888888888888,-52.072222222222216,54.074999999999996,71.29888888888888,51.27111111111111,144.20000000000002 +71.34833333333333,-52.10833333333333,54.1125,71.34833333333333,51.306666666666665,144.3 +71.39777777777778,-52.14444444444444,54.15,71.39777777777778,51.34222222222222,144.4 +71.44722222222222,-52.18055555555555,54.1875,71.44722222222222,51.37777777777778,144.5 +71.49666666666667,-52.21666666666666,54.225,71.49666666666667,51.413333333333334,144.6 +71.54611111111112,-52.25277777777777,54.262499999999996,71.54611111111112,51.44888888888889,144.70000000000002 +71.59555555555555,-52.288888888888884,54.3,71.59555555555555,51.48444444444444,144.8 +71.645,-52.324999999999996,54.3375,71.645,51.52,144.9 +71.69444444444444,-52.36111111111111,54.375,71.69444444444444,51.55555555555556,145.0 +71.74388888888889,-52.39722222222222,54.4125,71.74388888888889,51.59111111111111,145.1 +71.79333333333334,-52.43333333333333,54.449999999999996,71.79333333333334,51.626666666666665,145.20000000000002 +71.84277777777778,-52.46944444444444,54.4875,71.84277777777778,51.66222222222222,145.3 +71.89222222222222,-52.50555555555555,54.525,71.89222222222222,51.69777777777778,145.4 +71.94166666666666,-52.541666666666664,54.5625,71.94166666666666,51.733333333333334,145.5 +71.99111111111111,-52.577777777777776,54.6,71.99111111111111,51.76888888888889,145.6 +72.04055555555556,-52.61388888888889,54.637499999999996,72.04055555555556,51.80444444444444,145.70000000000002 +72.09,-52.65,54.675,72.09,51.84,145.8 +72.13944444444445,-52.6861111111111,54.7125,72.13944444444445,51.87555555555556,145.9 +72.18888888888888,-52.722222222222214,54.75,72.18888888888888,51.91111111111111,146.0 +72.23833333333333,-52.758333333333326,54.7875,72.23833333333333,51.946666666666665,146.1 +72.28777777777778,-52.79444444444444,54.824999999999996,72.28777777777778,51.98222222222222,146.20000000000002 +72.33722222222222,-52.83055555555555,54.8625,72.33722222222222,52.01777777777778,146.3 +72.38666666666667,-52.86666666666666,54.9,72.38666666666667,52.053333333333335,146.4 +72.4361111111111,-52.90277777777777,54.9375,72.4361111111111,52.08888888888889,146.5 +72.48555555555555,-52.93888888888888,54.975,72.48555555555555,52.12444444444444,146.6 +72.535,-52.974999999999994,55.012499999999996,72.535,52.16,146.70000000000002 +72.58444444444444,-53.011111111111106,55.05,72.58444444444444,52.19555555555556,146.8 +72.63388888888889,-53.04722222222222,55.0875,72.63388888888889,52.23111111111111,146.9 +72.68333333333334,-53.08333333333333,55.125,72.68333333333334,52.266666666666666,147.0 +72.73277777777777,-53.11944444444444,55.1625,72.73277777777777,52.30222222222222,147.1 +72.78222222222222,-53.15555555555555,55.199999999999996,72.78222222222222,52.33777777777778,147.20000000000002 +72.83166666666666,-53.19166666666666,55.2375,72.83166666666666,52.373333333333335,147.3 +72.88111111111111,-53.227777777777774,55.275,72.88111111111111,52.40888888888889,147.4 +72.93055555555556,-53.263888888888886,55.3125,72.93055555555556,52.44444444444444,147.5 +72.98,-53.3,55.35,72.98,52.48,147.6 +73.02944444444444,-53.33611111111111,55.387499999999996,73.02944444444444,52.51555555555556,147.70000000000002 +73.07888888888888,-53.37222222222222,55.425,73.07888888888888,52.55111111111111,147.8 +73.12833333333333,-53.40833333333333,55.4625,73.12833333333333,52.586666666666666,147.9 +73.17777777777778,-53.44444444444444,55.5,73.17777777777778,52.62222222222222,148.0 +73.22722222222222,-53.48055555555555,55.5375,73.22722222222222,52.65777777777778,148.1 +73.27666666666667,-53.51666666666666,55.574999999999996,73.27666666666667,52.693333333333335,148.20000000000002 +73.3261111111111,-53.55277777777777,55.6125,73.3261111111111,52.72888888888889,148.3 +73.37555555555555,-53.58888888888888,55.65,73.37555555555555,52.76444444444444,148.4 +73.425,-53.62499999999999,55.6875,73.425,52.8,148.5 +73.47444444444444,-53.661111111111104,55.725,73.47444444444444,52.83555555555556,148.6 +73.52388888888889,-53.697222222222216,55.762499999999996,73.52388888888889,52.87111111111111,148.70000000000002 +73.57333333333334,-53.73333333333333,55.8,73.57333333333334,52.906666666666666,148.8 +73.62277777777777,-53.76944444444444,55.8375,73.62277777777777,52.94222222222222,148.9 +73.67222222222222,-53.80555555555555,55.875,73.67222222222222,52.977777777777774,149.0 +73.72166666666666,-53.84166666666666,55.9125,73.72166666666666,53.013333333333335,149.1 +73.77111111111111,-53.87777777777777,55.949999999999996,73.77111111111111,53.04888888888889,149.20000000000002 +73.82055555555556,-53.913888888888884,55.9875,73.82055555555556,53.08444444444444,149.3 +73.87,-53.949999999999996,56.025,73.87,53.12,149.4 +73.91944444444444,-53.98611111111111,56.0625,73.91944444444444,53.15555555555556,149.5 +73.96888888888888,-54.02222222222222,56.1,73.96888888888888,53.19111111111111,149.6 +74.01833333333333,-54.05833333333333,56.137499999999996,74.01833333333333,53.22666666666667,149.70000000000002 +74.06777777777778,-54.09444444444444,56.175,74.06777777777778,53.26222222222222,149.8 +74.11722222222222,-54.13055555555555,56.2125,74.11722222222222,53.297777777777775,149.9 +74.16666666666667,-54.166666666666664,56.25,74.16666666666667,53.333333333333336,150.0 +74.2161111111111,-54.202777777777776,56.2875,74.2161111111111,53.36888888888889,150.1 +74.26555555555555,-54.23888888888889,56.324999999999996,74.26555555555555,53.404444444444444,150.20000000000002 +74.315,-54.27499999999999,56.3625,74.315,53.44,150.3 +74.36444444444444,-54.3111111111111,56.4,74.36444444444444,53.47555555555556,150.4 +74.41388888888889,-54.347222222222214,56.4375,74.41388888888889,53.51111111111111,150.5 +74.46333333333334,-54.383333333333326,56.475,74.46333333333334,53.54666666666667,150.6 +74.51277777777777,-54.41944444444444,56.512499999999996,74.51277777777777,53.58222222222222,150.70000000000002 +74.56222222222222,-54.45555555555555,56.55,74.56222222222222,53.617777777777775,150.8 +74.61166666666666,-54.49166666666666,56.5875,74.61166666666666,53.653333333333336,150.9 +74.66111111111111,-54.52777777777777,56.625,74.66111111111111,53.68888888888889,151.0 +74.71055555555556,-54.56388888888888,56.6625,74.71055555555556,53.724444444444444,151.1 +74.76,-54.599999999999994,56.699999999999996,74.76,53.76,151.20000000000002 +74.80944444444444,-54.636111111111106,56.7375,74.80944444444444,53.79555555555555,151.3 +74.85888888888888,-54.67222222222222,56.775,74.85888888888888,53.83111111111111,151.4 +74.90833333333333,-54.70833333333333,56.8125,74.90833333333333,53.86666666666667,151.5 +74.95777777777778,-54.74444444444444,56.85,74.95777777777778,53.90222222222222,151.6 +75.00722222222223,-54.78055555555555,56.887499999999996,75.00722222222223,53.937777777777775,151.70000000000002 +75.05666666666667,-54.81666666666666,56.925,75.05666666666667,53.973333333333336,151.8 +75.1061111111111,-54.852777777777774,56.9625,75.1061111111111,54.00888888888889,151.9 +75.15555555555555,-54.888888888888886,57.0,75.15555555555555,54.044444444444444,152.0 +75.205,-54.925,57.0375,75.205,54.08,152.1 +75.25444444444445,-54.96111111111111,57.074999999999996,75.25444444444445,54.11555555555555,152.20000000000002 +75.30388888888889,-54.99722222222222,57.1125,75.30388888888889,54.15111111111111,152.3 +75.35333333333334,-55.03333333333333,57.15,75.35333333333334,54.18666666666667,152.4 +75.40277777777777,-55.069444444444436,57.1875,75.40277777777777,54.22222222222222,152.5 +75.45222222222222,-55.10555555555555,57.225,75.45222222222222,54.257777777777775,152.6 +75.50166666666667,-55.14166666666666,57.262499999999996,75.50166666666667,54.29333333333334,152.70000000000002 +75.55111111111111,-55.17777777777777,57.3,75.55111111111111,54.32888888888889,152.8 +75.60055555555556,-55.21388888888888,57.3375,75.60055555555556,54.364444444444445,152.9 +75.65,-55.24999999999999,57.375,75.65,54.4,153.0 +75.69944444444444,-55.286111111111104,57.4125,75.69944444444444,54.43555555555555,153.1 +75.74888888888889,-55.322222222222216,57.449999999999996,75.74888888888889,54.471111111111114,153.20000000000002 +75.79833333333333,-55.35833333333333,57.4875,75.79833333333333,54.50666666666667,153.3 +75.84777777777778,-55.39444444444444,57.525,75.84777777777778,54.54222222222222,153.4 +75.89722222222223,-55.43055555555555,57.5625,75.89722222222223,54.577777777777776,153.5 +75.94666666666666,-55.46666666666666,57.599999999999994,75.94666666666666,54.61333333333333,153.60000000000002 +75.9961111111111,-55.50277777777777,57.637499999999996,75.9961111111111,54.64888888888889,153.70000000000002 +76.04555555555555,-55.538888888888884,57.675,76.04555555555555,54.684444444444445,153.8 +76.095,-55.574999999999996,57.7125,76.095,54.72,153.9 +76.14444444444445,-55.61111111111111,57.75,76.14444444444445,54.75555555555555,154.0 +76.19388888888889,-55.64722222222222,57.787499999999994,76.19388888888889,54.791111111111114,154.10000000000002 +76.24333333333333,-55.68333333333333,57.824999999999996,76.24333333333333,54.82666666666667,154.20000000000002 +76.29277777777777,-55.71944444444444,57.8625,76.29277777777777,54.86222222222222,154.3 +76.34222222222222,-55.75555555555555,57.9,76.34222222222222,54.897777777777776,154.4 +76.39166666666667,-55.791666666666664,57.9375,76.39166666666667,54.93333333333333,154.5 +76.44111111111111,-55.827777777777776,57.974999999999994,76.44111111111111,54.96888888888889,154.60000000000002 +76.49055555555556,-55.86388888888889,58.012499999999996,76.49055555555556,55.004444444444445,154.70000000000002 +76.53999999999999,-55.89999999999999,58.05,76.53999999999999,55.04,154.8 +76.58944444444444,-55.9361111111111,58.0875,76.58944444444444,55.07555555555555,154.9 +76.63888888888889,-55.972222222222214,58.125,76.63888888888889,55.111111111111114,155.0 +76.68833333333333,-56.008333333333326,58.162499999999994,76.68833333333333,55.14666666666667,155.10000000000002 +76.73777777777778,-56.04444444444444,58.199999999999996,76.73777777777778,55.18222222222222,155.20000000000002 +76.78722222222223,-56.08055555555555,58.2375,76.78722222222223,55.217777777777776,155.3 +76.83666666666666,-56.11666666666666,58.275,76.83666666666666,55.25333333333333,155.4 +76.8861111111111,-56.15277777777777,58.3125,76.8861111111111,55.28888888888889,155.5 +76.93555555555555,-56.18888888888888,58.349999999999994,76.93555555555555,55.324444444444445,155.60000000000002 +76.985,-56.224999999999994,58.387499999999996,76.985,55.36,155.70000000000002 +77.03444444444445,-56.261111111111106,58.425,77.03444444444445,55.39555555555555,155.8 +77.0838888888889,-56.29722222222222,58.4625,77.0838888888889,55.431111111111115,155.9 +77.13333333333333,-56.33333333333333,58.5,77.13333333333333,55.46666666666667,156.0 +77.18277777777777,-56.36944444444444,58.537499999999994,77.18277777777777,55.50222222222222,156.10000000000002 +77.23222222222222,-56.40555555555555,58.574999999999996,77.23222222222222,55.53777777777778,156.20000000000002 +77.28166666666667,-56.44166666666666,58.6125,77.28166666666667,55.57333333333333,156.3 +77.33111111111111,-56.477777777777774,58.65,77.33111111111111,55.60888888888889,156.4 +77.38055555555556,-56.513888888888886,58.6875,77.38055555555556,55.644444444444446,156.5 +77.42999999999999,-56.55,58.724999999999994,77.42999999999999,55.68,156.60000000000002 +77.47944444444444,-56.58611111111111,58.762499999999996,77.47944444444444,55.715555555555554,156.70000000000002 +77.52888888888889,-56.62222222222222,58.8,77.52888888888889,55.75111111111111,156.8 +77.57833333333333,-56.65833333333333,58.8375,77.57833333333333,55.78666666666667,156.9 +77.62777777777778,-56.694444444444436,58.875,77.62777777777778,55.82222222222222,157.0 +77.67722222222223,-56.73055555555555,58.912499999999994,77.67722222222223,55.85777777777778,157.10000000000002 +77.72666666666666,-56.76666666666666,58.949999999999996,77.72666666666666,55.89333333333333,157.20000000000002 +77.7761111111111,-56.80277777777777,58.9875,77.7761111111111,55.92888888888889,157.3 +77.82555555555555,-56.83888888888888,59.025,77.82555555555555,55.964444444444446,157.4 +77.875,-56.87499999999999,59.0625,77.875,56.0,157.5 +77.92444444444445,-56.911111111111104,59.099999999999994,77.92444444444445,56.035555555555554,157.60000000000002 +77.9738888888889,-56.947222222222216,59.137499999999996,77.9738888888889,56.07111111111111,157.70000000000002 +78.02333333333333,-56.98333333333333,59.175,78.02333333333333,56.10666666666667,157.8 +78.07277777777777,-57.01944444444444,59.2125,78.07277777777777,56.14222222222222,157.9 +78.12222222222222,-57.05555555555555,59.25,78.12222222222222,56.17777777777778,158.0 +78.17166666666667,-57.09166666666666,59.287499999999994,78.17166666666667,56.21333333333333,158.10000000000002 +78.22111111111111,-57.12777777777777,59.324999999999996,78.22111111111111,56.24888888888889,158.20000000000002 +78.27055555555556,-57.163888888888884,59.3625,78.27055555555556,56.284444444444446,158.3 +78.32,-57.199999999999996,59.4,78.32,56.32,158.4 +78.36944444444444,-57.23611111111111,59.4375,78.36944444444444,56.355555555555554,158.5 +78.41888888888889,-57.27222222222222,59.474999999999994,78.41888888888889,56.39111111111111,158.60000000000002 +78.46833333333333,-57.30833333333333,59.512499999999996,78.46833333333333,56.42666666666667,158.70000000000002 +78.51777777777778,-57.34444444444444,59.55,78.51777777777778,56.46222222222222,158.8 +78.56722222222223,-57.38055555555555,59.5875,78.56722222222223,56.49777777777778,158.9 +78.61666666666666,-57.416666666666664,59.625,78.61666666666666,56.53333333333333,159.0 +78.6661111111111,-57.452777777777776,59.662499999999994,78.6661111111111,56.568888888888885,159.10000000000002 +78.71555555555555,-57.48888888888888,59.699999999999996,78.71555555555555,56.60444444444445,159.20000000000002 +78.765,-57.52499999999999,59.7375,78.765,56.64,159.3 +78.81444444444445,-57.5611111111111,59.775,78.81444444444445,56.675555555555555,159.4 +78.8638888888889,-57.597222222222214,59.8125,78.8638888888889,56.71111111111111,159.5 +78.91333333333333,-57.633333333333326,59.849999999999994,78.91333333333333,56.74666666666667,159.60000000000002 +78.96277777777777,-57.66944444444444,59.887499999999996,78.96277777777777,56.782222222222224,159.70000000000002 +79.01222222222222,-57.70555555555555,59.925,79.01222222222222,56.81777777777778,159.8 +79.06166666666667,-57.74166666666666,59.9625,79.06166666666667,56.85333333333333,159.9 +79.11111111111111,-57.77777777777777,60.0,79.11111111111111,56.888888888888886,160.0 +79.16055555555556,-57.81388888888888,60.037499999999994,79.16055555555556,56.92444444444445,160.10000000000002 +79.21,-57.849999999999994,60.074999999999996,79.21,56.96,160.20000000000002 +79.25944444444444,-57.886111111111106,60.1125,79.25944444444444,56.995555555555555,160.3 +79.30888888888889,-57.92222222222222,60.15,79.30888888888889,57.03111111111111,160.4 +79.35833333333333,-57.95833333333333,60.1875,79.35833333333333,57.06666666666667,160.5 +79.40777777777778,-57.99444444444444,60.224999999999994,79.40777777777778,57.102222222222224,160.60000000000002 +79.45722222222223,-58.03055555555555,60.262499999999996,79.45722222222223,57.13777777777778,160.70000000000002 +79.50666666666666,-58.06666666666666,60.3,79.50666666666666,57.17333333333333,160.8 +79.55611111111111,-58.102777777777774,60.3375,79.55611111111111,57.208888888888886,160.9 +79.60555555555555,-58.138888888888886,60.375,79.60555555555555,57.24444444444445,161.0 +79.655,-58.175,60.412499999999994,79.655,57.28,161.10000000000002 +79.70444444444445,-58.21111111111111,60.449999999999996,79.70444444444445,57.315555555555555,161.20000000000002 +79.75388888888888,-58.24722222222222,60.4875,79.75388888888888,57.35111111111111,161.3 +79.80333333333333,-58.283333333333324,60.525,79.80333333333333,57.38666666666666,161.4 +79.85277777777777,-58.319444444444436,60.5625,79.85277777777777,57.422222222222224,161.5 +79.90222222222222,-58.35555555555555,60.599999999999994,79.90222222222222,57.45777777777778,161.60000000000002 +79.95166666666667,-58.39166666666666,60.637499999999996,79.95166666666667,57.49333333333333,161.70000000000002 +80.00111111111111,-58.42777777777777,60.675,80.00111111111111,57.528888888888886,161.8 +80.05055555555555,-58.46388888888888,60.7125,80.05055555555555,57.56444444444445,161.9 +80.1,-58.49999999999999,60.75,80.1,57.6,162.0 +80.14944444444444,-58.536111111111104,60.787499999999994,80.14944444444444,57.635555555555555,162.10000000000002 +80.19888888888889,-58.572222222222216,60.824999999999996,80.19888888888889,57.67111111111111,162.20000000000002 +80.24833333333333,-58.60833333333333,60.8625,80.24833333333333,57.70666666666666,162.3 +80.29777777777778,-58.64444444444444,60.9,80.29777777777778,57.742222222222225,162.4 +80.34722222222221,-58.68055555555555,60.9375,80.34722222222221,57.77777777777778,162.5 +80.39666666666666,-58.71666666666666,60.974999999999994,80.39666666666666,57.81333333333333,162.60000000000002 +80.44611111111111,-58.75277777777777,61.012499999999996,80.44611111111111,57.84888888888889,162.70000000000002 +80.49555555555555,-58.788888888888884,61.05,80.49555555555555,57.88444444444445,162.8 +80.545,-58.824999999999996,61.0875,80.545,57.92,162.9 +80.59444444444445,-58.86111111111111,61.125,80.59444444444445,57.955555555555556,163.0 +80.64388888888888,-58.89722222222222,61.162499999999994,80.64388888888888,57.99111111111111,163.10000000000002 +80.69333333333333,-58.93333333333333,61.199999999999996,80.69333333333333,58.026666666666664,163.20000000000002 +80.74277777777777,-58.96944444444444,61.2375,80.74277777777777,58.062222222222225,163.3 +80.79222222222222,-59.00555555555555,61.275,80.79222222222222,58.09777777777778,163.4 +80.84166666666667,-59.041666666666664,61.3125,80.84166666666667,58.13333333333333,163.5 +80.89111111111112,-59.077777777777776,61.349999999999994,80.89111111111112,58.16888888888889,163.60000000000002 +80.94055555555555,-59.11388888888888,61.387499999999996,80.94055555555555,58.20444444444444,163.70000000000002 +80.99,-59.14999999999999,61.425,80.99,58.24,163.8 +81.03944444444444,-59.1861111111111,61.4625,81.03944444444444,58.275555555555556,163.9 +81.08888888888889,-59.222222222222214,61.5,81.08888888888889,58.31111111111111,164.0 +81.13833333333334,-59.258333333333326,61.537499999999994,81.13833333333334,58.346666666666664,164.10000000000002 +81.18777777777778,-59.29444444444444,61.574999999999996,81.18777777777778,58.382222222222225,164.20000000000002 +81.23722222222221,-59.33055555555555,61.6125,81.23722222222221,58.41777777777778,164.3 +81.28666666666666,-59.36666666666666,61.65,81.28666666666666,58.45333333333333,164.4 +81.33611111111111,-59.40277777777777,61.6875,81.33611111111111,58.48888888888889,164.5 +81.38555555555556,-59.43888888888888,61.724999999999994,81.38555555555556,58.52444444444444,164.60000000000002 +81.435,-59.474999999999994,61.762499999999996,81.435,58.56,164.70000000000002 +81.48444444444445,-59.511111111111106,61.8,81.48444444444445,58.595555555555556,164.8 +81.53388888888888,-59.54722222222222,61.8375,81.53388888888888,58.63111111111111,164.9 +81.58333333333333,-59.58333333333333,61.875,81.58333333333333,58.666666666666664,165.0 +81.63277777777778,-59.61944444444444,61.912499999999994,81.63277777777778,58.702222222222225,165.10000000000002 +81.68222222222222,-59.65555555555555,61.949999999999996,81.68222222222222,58.73777777777778,165.20000000000002 +81.73166666666667,-59.69166666666666,61.9875,81.73166666666667,58.77333333333333,165.3 +81.78111111111112,-59.727777777777774,62.025,81.78111111111112,58.80888888888889,165.4 +81.83055555555555,-59.763888888888886,62.0625,81.83055555555555,58.84444444444444,165.5 +81.88,-59.8,62.099999999999994,81.88,58.88,165.60000000000002 +81.92944444444444,-59.83611111111111,62.137499999999996,81.92944444444444,58.91555555555556,165.70000000000002 +81.97888888888889,-59.87222222222222,62.175,81.97888888888889,58.95111111111111,165.8 +82.02833333333334,-59.908333333333324,62.2125,82.02833333333334,58.986666666666665,165.9 +82.07777777777778,-59.944444444444436,62.25,82.07777777777778,59.022222222222226,166.0 +82.12722222222222,-59.98055555555555,62.287499999999994,82.12722222222222,59.05777777777778,166.10000000000002 +82.17666666666666,-60.01666666666666,62.324999999999996,82.17666666666666,59.093333333333334,166.20000000000002 +82.22611111111111,-60.05277777777777,62.3625,82.22611111111111,59.12888888888889,166.3 +82.27555555555556,-60.08888888888888,62.4,82.27555555555556,59.16444444444444,166.4 +82.325,-60.12499999999999,62.4375,82.325,59.2,166.5 +82.37444444444445,-60.161111111111104,62.474999999999994,82.37444444444445,59.23555555555556,166.60000000000002 +82.42388888888888,-60.197222222222216,62.512499999999996,82.42388888888888,59.27111111111111,166.70000000000002 +82.47333333333333,-60.23333333333333,62.55,82.47333333333333,59.306666666666665,166.8 +82.52277777777778,-60.26944444444444,62.5875,82.52277777777778,59.34222222222222,166.9 +82.57222222222222,-60.30555555555555,62.625,82.57222222222222,59.37777777777778,167.0 +82.62166666666667,-60.34166666666666,62.662499999999994,82.62166666666667,59.413333333333334,167.10000000000002 +82.67111111111112,-60.37777777777777,62.699999999999996,82.67111111111112,59.44888888888889,167.20000000000002 +82.72055555555555,-60.413888888888884,62.7375,82.72055555555555,59.48444444444444,167.3 +82.77,-60.449999999999996,62.775,82.77,59.52,167.4 +82.81944444444444,-60.48611111111111,62.8125,82.81944444444444,59.55555555555556,167.5 +82.86888888888889,-60.52222222222222,62.849999999999994,82.86888888888889,59.59111111111111,167.60000000000002 +82.91833333333334,-60.55833333333333,62.887499999999996,82.91833333333334,59.626666666666665,167.70000000000002 +82.96777777777778,-60.59444444444444,62.925,82.96777777777778,59.66222222222222,167.8 +83.01722222222222,-60.63055555555555,62.9625,83.01722222222222,59.69777777777778,167.9 +83.06666666666666,-60.666666666666664,63.0,83.06666666666666,59.733333333333334,168.0 +83.11611111111111,-60.70277777777777,63.037499999999994,83.11611111111111,59.76888888888889,168.10000000000002 +83.16555555555556,-60.73888888888888,63.074999999999996,83.16555555555556,59.80444444444444,168.20000000000002 +83.215,-60.77499999999999,63.1125,83.215,59.84,168.3 +83.26444444444444,-60.8111111111111,63.15,83.26444444444444,59.87555555555556,168.4 +83.31388888888888,-60.847222222222214,63.1875,83.31388888888888,59.91111111111111,168.5 +83.36333333333333,-60.883333333333326,63.224999999999994,83.36333333333333,59.946666666666665,168.60000000000002 +83.41277777777778,-60.91944444444444,63.262499999999996,83.41277777777778,59.98222222222222,168.70000000000002 +83.46222222222222,-60.95555555555555,63.3,83.46222222222222,60.01777777777778,168.8 +83.51166666666667,-60.99166666666666,63.3375,83.51166666666667,60.053333333333335,168.9 +83.5611111111111,-61.02777777777777,63.375,83.5611111111111,60.08888888888889,169.0 +83.61055555555555,-61.06388888888888,63.412499999999994,83.61055555555555,60.12444444444444,169.10000000000002 +83.66,-61.099999999999994,63.449999999999996,83.66,60.16,169.20000000000002 +83.70944444444444,-61.136111111111106,63.4875,83.70944444444444,60.19555555555556,169.3 +83.75888888888889,-61.17222222222222,63.525,83.75888888888889,60.23111111111111,169.4 +83.80833333333334,-61.20833333333333,63.5625,83.80833333333334,60.266666666666666,169.5 +83.85777777777777,-61.24444444444444,63.599999999999994,83.85777777777777,60.30222222222222,169.60000000000002 +83.90722222222222,-61.28055555555555,63.637499999999996,83.90722222222222,60.33777777777778,169.70000000000002 +83.95666666666666,-61.31666666666666,63.675,83.95666666666666,60.373333333333335,169.8 +84.00611111111111,-61.352777777777774,63.7125,84.00611111111111,60.40888888888889,169.9 +84.05555555555556,-61.388888888888886,63.75,84.05555555555556,60.44444444444444,170.0 +84.105,-61.425,63.787499999999994,84.105,60.48,170.10000000000002 +84.15444444444444,-61.46111111111111,63.824999999999996,84.15444444444444,60.51555555555556,170.20000000000002 +84.20388888888888,-61.49722222222221,63.8625,84.20388888888888,60.55111111111111,170.3 +84.25333333333333,-61.533333333333324,63.9,84.25333333333333,60.586666666666666,170.4 +84.30277777777778,-61.569444444444436,63.9375,84.30277777777778,60.62222222222222,170.5 +84.35222222222222,-61.60555555555555,63.974999999999994,84.35222222222222,60.65777777777778,170.60000000000002 +84.40166666666667,-61.64166666666666,64.0125,84.40166666666667,60.693333333333335,170.70000000000002 +84.4511111111111,-61.67777777777777,64.05,84.4511111111111,60.72888888888889,170.8 +84.50055555555555,-61.71388888888888,64.08749999999999,84.50055555555555,60.76444444444444,170.9 +84.55,-61.74999999999999,64.125,84.55,60.8,171.0 +84.59944444444444,-61.786111111111104,64.1625,84.59944444444444,60.83555555555556,171.10000000000002 +84.64888888888889,-61.822222222222216,64.2,84.64888888888889,60.87111111111111,171.20000000000002 +84.69833333333334,-61.85833333333333,64.2375,84.69833333333334,60.906666666666666,171.3 +84.74777777777777,-61.89444444444444,64.27499999999999,84.74777777777777,60.94222222222222,171.4 +84.79722222222222,-61.93055555555555,64.3125,84.79722222222222,60.977777777777774,171.5 +84.84666666666666,-61.96666666666666,64.35,84.84666666666666,61.013333333333335,171.60000000000002 +84.89611111111111,-62.00277777777777,64.3875,84.89611111111111,61.04888888888889,171.70000000000002 +84.94555555555556,-62.038888888888884,64.425,84.94555555555556,61.08444444444444,171.8 +84.995,-62.074999999999996,64.46249999999999,84.995,61.12,171.9 +85.04444444444444,-62.11111111111111,64.5,85.04444444444444,61.15555555555556,172.0 +85.09388888888888,-62.14722222222222,64.5375,85.09388888888888,61.19111111111111,172.10000000000002 +85.14333333333333,-62.18333333333333,64.575,85.14333333333333,61.22666666666667,172.20000000000002 +85.19277777777778,-62.21944444444444,64.6125,85.19277777777778,61.26222222222222,172.3 +85.24222222222222,-62.25555555555555,64.64999999999999,85.24222222222222,61.297777777777775,172.4 +85.29166666666667,-62.291666666666664,64.6875,85.29166666666667,61.333333333333336,172.5 +85.3411111111111,-62.32777777777777,64.725,85.3411111111111,61.36888888888889,172.60000000000002 +85.39055555555555,-62.36388888888888,64.7625,85.39055555555555,61.404444444444444,172.70000000000002 +85.44,-62.39999999999999,64.8,85.44,61.44,172.8 +85.48944444444444,-62.4361111111111,64.83749999999999,85.48944444444444,61.47555555555556,172.9 +85.53888888888889,-62.472222222222214,64.875,85.53888888888889,61.51111111111111,173.0 +85.58833333333334,-62.508333333333326,64.9125,85.58833333333334,61.54666666666667,173.10000000000002 +85.63777777777777,-62.54444444444444,64.95,85.63777777777777,61.58222222222222,173.20000000000002 +85.68722222222222,-62.58055555555555,64.9875,85.68722222222222,61.617777777777775,173.3 +85.73666666666666,-62.61666666666666,65.02499999999999,85.73666666666666,61.653333333333336,173.4 +85.78611111111111,-62.65277777777777,65.0625,85.78611111111111,61.68888888888889,173.5 +85.83555555555556,-62.68888888888888,65.1,85.83555555555556,61.724444444444444,173.60000000000002 +85.885,-62.724999999999994,65.1375,85.885,61.76,173.70000000000002 +85.93444444444444,-62.761111111111106,65.175,85.93444444444444,61.79555555555555,173.8 +85.98388888888888,-62.79722222222222,65.21249999999999,85.98388888888888,61.83111111111111,173.9 +86.03333333333333,-62.83333333333333,65.25,86.03333333333333,61.86666666666667,174.0 +86.08277777777778,-62.86944444444444,65.2875,86.08277777777778,61.90222222222222,174.10000000000002 +86.13222222222223,-62.90555555555555,65.325,86.13222222222223,61.937777777777775,174.20000000000002 +86.18166666666667,-62.94166666666666,65.3625,86.18166666666667,61.973333333333336,174.3 +86.2311111111111,-62.977777777777774,65.39999999999999,86.2311111111111,62.00888888888889,174.4 +86.28055555555555,-63.013888888888886,65.4375,86.28055555555555,62.044444444444444,174.5 +86.33,-63.05,65.475,86.33,62.08,174.60000000000002 +86.37944444444445,-63.08611111111111,65.5125,86.37944444444445,62.11555555555555,174.70000000000002 +86.42888888888889,-63.12222222222221,65.55,86.42888888888889,62.15111111111111,174.8 +86.47833333333334,-63.158333333333324,65.58749999999999,86.47833333333334,62.18666666666667,174.9 +86.52777777777777,-63.194444444444436,65.625,86.52777777777777,62.22222222222222,175.0 +86.57722222222222,-63.23055555555555,65.6625,86.57722222222222,62.257777777777775,175.10000000000002 +86.62666666666667,-63.26666666666666,65.7,86.62666666666667,62.29333333333334,175.20000000000002 +86.67611111111111,-63.30277777777777,65.7375,86.67611111111111,62.32888888888889,175.3 +86.72555555555556,-63.33888888888888,65.77499999999999,86.72555555555556,62.364444444444445,175.4 +86.775,-63.37499999999999,65.8125,86.775,62.4,175.5 +86.82444444444444,-63.411111111111104,65.85,86.82444444444444,62.43555555555555,175.60000000000002 +86.87388888888889,-63.447222222222216,65.8875,86.87388888888889,62.471111111111114,175.70000000000002 +86.92333333333333,-63.48333333333333,65.925,86.92333333333333,62.50666666666667,175.8 +86.97277777777778,-63.51944444444444,65.96249999999999,86.97277777777778,62.54222222222222,175.9 +87.02222222222223,-63.55555555555555,66.0,87.02222222222223,62.577777777777776,176.0 +87.07166666666666,-63.59166666666666,66.0375,87.07166666666666,62.61333333333333,176.10000000000002 +87.1211111111111,-63.62777777777777,66.075,87.1211111111111,62.64888888888889,176.20000000000002 +87.17055555555555,-63.663888888888884,66.1125,87.17055555555555,62.684444444444445,176.3 +87.22,-63.699999999999996,66.14999999999999,87.22,62.72,176.4 +87.26944444444445,-63.73611111111111,66.1875,87.26944444444445,62.75555555555555,176.5 +87.31888888888889,-63.77222222222222,66.225,87.31888888888889,62.791111111111114,176.60000000000002 +87.36833333333333,-63.80833333333333,66.2625,87.36833333333333,62.82666666666667,176.70000000000002 +87.41777777777777,-63.84444444444444,66.3,87.41777777777777,62.86222222222222,176.8 +87.46722222222222,-63.88055555555555,66.33749999999999,87.46722222222222,62.897777777777776,176.9 +87.51666666666667,-63.91666666666666,66.375,87.51666666666667,62.93333333333333,177.0 +87.56611111111111,-63.95277777777777,66.4125,87.56611111111111,62.96888888888889,177.10000000000002 +87.61555555555556,-63.98888888888888,66.45,87.61555555555556,63.004444444444445,177.20000000000002 +87.66499999999999,-64.02499999999999,66.4875,87.66499999999999,63.04,177.3 +87.71444444444444,-64.0611111111111,66.52499999999999,87.71444444444444,63.07555555555555,177.4 +87.76388888888889,-64.09722222222221,66.5625,87.76388888888889,63.111111111111114,177.5 +87.81333333333333,-64.13333333333333,66.6,87.81333333333333,63.14666666666667,177.60000000000002 +87.86277777777778,-64.16944444444444,66.6375,87.86277777777778,63.18222222222222,177.70000000000002 +87.91222222222223,-64.20555555555555,66.675,87.91222222222223,63.217777777777776,177.8 +87.96166666666666,-64.24166666666666,66.71249999999999,87.96166666666666,63.25333333333333,177.9 +88.0111111111111,-64.27777777777777,66.75,88.0111111111111,63.28888888888889,178.0 +88.06055555555555,-64.31388888888888,66.7875,88.06055555555555,63.324444444444445,178.10000000000002 +88.11,-64.35,66.825,88.11,63.36,178.20000000000002 +88.15944444444445,-64.3861111111111,66.8625,88.15944444444445,63.39555555555555,178.3 +88.2088888888889,-64.42222222222222,66.89999999999999,88.2088888888889,63.431111111111115,178.4 +88.25833333333333,-64.45833333333333,66.9375,88.25833333333333,63.46666666666667,178.5 +88.30777777777777,-64.49444444444444,66.975,88.30777777777777,63.50222222222222,178.60000000000002 +88.35722222222222,-64.53055555555555,67.0125,88.35722222222222,63.53777777777778,178.70000000000002 +88.40666666666667,-64.56666666666666,67.05,88.40666666666667,63.57333333333333,178.8 +88.45611111111111,-64.60277777777777,67.08749999999999,88.45611111111111,63.60888888888889,178.9 +88.50555555555556,-64.63888888888889,67.125,88.50555555555556,63.644444444444446,179.0 +88.55499999999999,-64.675,67.1625,88.55499999999999,63.68,179.10000000000002 +88.60444444444444,-64.71111111111111,67.2,88.60444444444444,63.715555555555554,179.20000000000002 +88.65388888888889,-64.74722222222222,67.2375,88.65388888888889,63.75111111111111,179.3 +88.70333333333333,-64.78333333333333,67.27499999999999,88.70333333333333,63.78666666666667,179.4 +88.75277777777778,-64.81944444444444,67.3125,88.75277777777778,63.82222222222222,179.5 +88.80222222222223,-64.85555555555555,67.35,88.80222222222223,63.85777777777778,179.60000000000002 +88.85166666666666,-64.89166666666667,67.3875,88.85166666666666,63.89333333333333,179.70000000000002 +88.9011111111111,-64.92777777777778,67.425,88.9011111111111,63.92888888888889,179.8 +88.95055555555555,-64.96388888888889,67.46249999999999,88.95055555555555,63.964444444444446,179.9 +89.0,-65.0,67.5,89.0,64.0,180.0 +89.04944444444445,-65.03611111111111,67.5375,89.04944444444445,64.03555555555556,180.10000000000002 +89.0988888888889,-65.07222222222222,67.575,89.0988888888889,64.07111111111111,180.20000000000002 +89.14833333333333,-65.10833333333333,67.6125,89.14833333333333,64.10666666666667,180.3 +89.19777777777777,-65.14444444444443,67.64999999999999,89.19777777777777,64.14222222222222,180.4 +89.24722222222222,-65.18055555555554,67.6875,89.24722222222222,64.17777777777778,180.5 +89.29666666666667,-65.21666666666665,67.725,89.29666666666667,64.21333333333334,180.60000000000002 +89.34611111111111,-65.25277777777777,67.7625,89.34611111111111,64.24888888888889,180.70000000000002 +89.39555555555556,-65.28888888888888,67.8,89.39555555555556,64.28444444444445,180.8 +89.445,-65.32499999999999,67.83749999999999,89.445,64.32,180.9 +89.49444444444444,-65.3611111111111,67.875,89.49444444444444,64.35555555555555,181.0 +89.54388888888889,-65.39722222222221,67.9125,89.54388888888889,64.39111111111112,181.10000000000002 +89.59333333333333,-65.43333333333332,67.95,89.59333333333333,64.42666666666666,181.20000000000002 +89.64277777777778,-65.46944444444443,67.9875,89.64277777777778,64.46222222222222,181.3 +89.69222222222223,-65.50555555555555,68.02499999999999,89.69222222222223,64.49777777777778,181.4 +89.74166666666666,-65.54166666666666,68.0625,89.74166666666666,64.53333333333333,181.5 +89.7911111111111,-65.57777777777777,68.1,89.7911111111111,64.56888888888889,181.60000000000002 +89.84055555555555,-65.61388888888888,68.1375,89.84055555555555,64.60444444444444,181.70000000000002 +89.89,-65.64999999999999,68.175,89.89,64.64,181.8 +89.93944444444445,-65.6861111111111,68.21249999999999,89.93944444444445,64.67555555555556,181.9 +89.9888888888889,-65.72222222222221,68.25,89.9888888888889,64.71111111111111,182.0 +90.03833333333333,-65.75833333333333,68.2875,90.03833333333333,64.74666666666667,182.10000000000002 +90.08777777777777,-65.79444444444444,68.325,90.08777777777777,64.78222222222222,182.20000000000002 +90.13722222222222,-65.83055555555555,68.3625,90.13722222222222,64.81777777777778,182.3 +90.18666666666667,-65.86666666666666,68.39999999999999,90.18666666666667,64.85333333333334,182.4 +90.23611111111111,-65.90277777777777,68.4375,90.23611111111111,64.88888888888889,182.5 +90.28555555555556,-65.93888888888888,68.475,90.28555555555556,64.92444444444445,182.60000000000002 +90.335,-65.975,68.5125,90.335,64.96,182.70000000000002 +90.38444444444444,-66.0111111111111,68.55,90.38444444444444,64.99555555555555,182.8 +90.43388888888889,-66.04722222222222,68.58749999999999,90.43388888888889,65.03111111111112,182.9 +90.48333333333333,-66.08333333333333,68.625,90.48333333333333,65.06666666666666,183.0 +90.53277777777778,-66.11944444444444,68.6625,90.53277777777778,65.10222222222222,183.10000000000002 +90.58222222222221,-66.15555555555555,68.7,90.58222222222221,65.13777777777777,183.20000000000002 +90.63166666666666,-66.19166666666666,68.7375,90.63166666666666,65.17333333333333,183.3 +90.68111111111111,-66.22777777777777,68.77499999999999,90.68111111111111,65.2088888888889,183.4 +90.73055555555555,-66.26388888888889,68.8125,90.73055555555555,65.24444444444444,183.5 +90.78,-66.3,68.85,90.78,65.28,183.60000000000002 +90.82944444444445,-66.33611111111111,68.8875,90.82944444444445,65.31555555555556,183.70000000000002 +90.87888888888888,-66.37222222222222,68.925,90.87888888888888,65.35111111111111,183.8 +90.92833333333333,-66.40833333333333,68.96249999999999,90.92833333333333,65.38666666666667,183.9 +90.97777777777777,-66.44444444444444,69.0,90.97777777777777,65.42222222222222,184.0 +91.02722222222222,-66.48055555555555,69.0375,91.02722222222222,65.45777777777778,184.10000000000002 +91.07666666666667,-66.51666666666667,69.075,91.07666666666667,65.49333333333334,184.20000000000002 +91.12611111111111,-66.55277777777778,69.1125,91.12611111111111,65.52888888888889,184.3 +91.17555555555555,-66.58888888888889,69.14999999999999,91.17555555555555,65.56444444444445,184.4 +91.225,-66.625,69.1875,91.225,65.6,184.5 +91.27444444444444,-66.66111111111111,69.225,91.27444444444444,65.63555555555556,184.60000000000002 +91.32388888888889,-66.69722222222222,69.2625,91.32388888888889,65.67111111111112,184.70000000000002 +91.37333333333333,-66.73333333333332,69.3,91.37333333333333,65.70666666666666,184.8 +91.42277777777778,-66.76944444444443,69.33749999999999,91.42277777777778,65.74222222222222,184.9 +91.47222222222221,-66.80555555555554,69.375,91.47222222222221,65.77777777777777,185.0 +91.52166666666666,-66.84166666666665,69.4125,91.52166666666666,65.81333333333333,185.10000000000002 +91.57111111111111,-66.87777777777777,69.45,91.57111111111111,65.8488888888889,185.20000000000002 +91.62055555555555,-66.91388888888888,69.4875,91.62055555555555,65.88444444444444,185.3 +91.67,-66.94999999999999,69.52499999999999,91.67,65.92,185.4 +91.71944444444445,-66.9861111111111,69.5625,91.71944444444445,65.95555555555555,185.5 +91.76888888888888,-67.02222222222221,69.6,91.76888888888888,65.99111111111111,185.60000000000002 +91.81833333333333,-67.05833333333332,69.6375,91.81833333333333,66.02666666666667,185.70000000000002 +91.86777777777777,-67.09444444444443,69.675,91.86777777777777,66.06222222222222,185.8 +91.91722222222222,-67.13055555555555,69.71249999999999,91.91722222222222,66.09777777777778,185.9 +91.96666666666667,-67.16666666666666,69.75,91.96666666666667,66.13333333333334,186.0 +92.01611111111112,-67.20277777777777,69.7875,92.01611111111112,66.16888888888889,186.10000000000002 +92.06555555555555,-67.23888888888888,69.825,92.06555555555555,66.20444444444445,186.20000000000002 +92.115,-67.27499999999999,69.8625,92.115,66.24,186.3 +92.16444444444444,-67.3111111111111,69.89999999999999,92.16444444444444,66.27555555555556,186.4 +92.21388888888889,-67.34722222222221,69.9375,92.21388888888889,66.31111111111112,186.5 +92.26333333333334,-67.38333333333333,69.975,92.26333333333334,66.34666666666666,186.60000000000002 +92.31277777777778,-67.41944444444444,70.0125,92.31277777777778,66.38222222222223,186.70000000000002 +92.36222222222221,-67.45555555555555,70.05,92.36222222222221,66.41777777777777,186.8 +92.41166666666666,-67.49166666666666,70.08749999999999,92.41166666666666,66.45333333333333,186.9 +92.46111111111111,-67.52777777777777,70.125,92.46111111111111,66.4888888888889,187.0 +92.51055555555556,-67.56388888888888,70.1625,92.51055555555556,66.52444444444444,187.10000000000002 +92.56,-67.6,70.2,92.56,66.56,187.20000000000002 +92.60944444444445,-67.6361111111111,70.2375,92.60944444444445,66.59555555555555,187.3 +92.65888888888888,-67.67222222222222,70.27499999999999,92.65888888888888,66.63111111111111,187.4 +92.70833333333333,-67.70833333333333,70.3125,92.70833333333333,66.66666666666667,187.5 +92.75777777777778,-67.74444444444444,70.35,92.75777777777778,66.70222222222222,187.60000000000002 +92.80722222222222,-67.78055555555555,70.3875,92.80722222222222,66.73777777777778,187.70000000000002 +92.85666666666667,-67.81666666666666,70.425,92.85666666666667,66.77333333333333,187.8 +92.90611111111112,-67.85277777777777,70.46249999999999,92.90611111111112,66.80888888888889,187.9 +92.95555555555555,-67.88888888888889,70.5,92.95555555555555,66.84444444444445,188.0 +93.005,-67.925,70.5375,93.005,66.88,188.10000000000002 +93.05444444444444,-67.96111111111111,70.575,93.05444444444444,66.91555555555556,188.20000000000002 +93.10388888888889,-67.99722222222222,70.6125,93.10388888888889,66.95111111111112,188.3 +93.15333333333334,-68.03333333333333,70.64999999999999,93.15333333333334,66.98666666666666,188.4 +93.20277777777778,-68.06944444444444,70.6875,93.20277777777778,67.02222222222223,188.5 +93.25222222222222,-68.10555555555555,70.725,93.25222222222222,67.05777777777777,188.60000000000002 +93.30166666666666,-68.14166666666667,70.7625,93.30166666666666,67.09333333333333,188.70000000000002 +93.35111111111111,-68.17777777777778,70.8,93.35111111111111,67.1288888888889,188.8 +93.40055555555556,-68.21388888888889,70.83749999999999,93.40055555555556,67.16444444444444,188.9 +93.45,-68.25,70.875,93.45,67.2,189.0 +93.49944444444445,-68.28611111111111,70.9125,93.49944444444445,67.23555555555555,189.10000000000002 +93.54888888888888,-68.32222222222222,70.95,93.54888888888888,67.27111111111111,189.20000000000002 +93.59833333333333,-68.35833333333332,70.9875,93.59833333333333,67.30666666666667,189.3 +93.64777777777778,-68.39444444444443,71.02499999999999,93.64777777777778,67.34222222222222,189.4 +93.69722222222222,-68.43055555555554,71.0625,93.69722222222222,67.37777777777778,189.5 +93.74666666666667,-68.46666666666665,71.1,93.74666666666667,67.41333333333333,189.60000000000002 +93.79611111111112,-68.50277777777777,71.1375,93.79611111111112,67.44888888888889,189.70000000000002 +93.84555555555555,-68.53888888888888,71.175,93.84555555555555,67.48444444444445,189.8 +93.895,-68.57499999999999,71.21249999999999,93.895,67.52,189.9 +93.94444444444444,-68.6111111111111,71.25,93.94444444444444,67.55555555555556,190.0 +93.99388888888889,-68.64722222222221,71.2875,93.99388888888889,67.5911111111111,190.10000000000002 +94.04333333333334,-68.68333333333332,71.325,94.04333333333334,67.62666666666667,190.20000000000002 +94.09277777777777,-68.71944444444443,71.3625,94.09277777777777,67.66222222222223,190.3 +94.14222222222222,-68.75555555555555,71.39999999999999,94.14222222222222,67.69777777777777,190.4 +94.19166666666666,-68.79166666666666,71.4375,94.19166666666666,67.73333333333333,190.5 +94.24111111111111,-68.82777777777777,71.475,94.24111111111111,67.7688888888889,190.60000000000002 +94.29055555555556,-68.86388888888888,71.5125,94.29055555555556,67.80444444444444,190.70000000000002 +94.34,-68.89999999999999,71.55,94.34,67.84,190.8 +94.38944444444444,-68.9361111111111,71.58749999999999,94.38944444444444,67.87555555555555,190.9 +94.43888888888888,-68.97222222222221,71.625,94.43888888888888,67.91111111111111,191.0 +94.48833333333333,-69.00833333333333,71.6625,94.48833333333333,67.94666666666667,191.10000000000002 +94.53777777777778,-69.04444444444444,71.7,94.53777777777778,67.98222222222222,191.20000000000002 +94.58722222222222,-69.08055555555555,71.7375,94.58722222222222,68.01777777777778,191.3 +94.63666666666667,-69.11666666666666,71.77499999999999,94.63666666666667,68.05333333333333,191.4 +94.6861111111111,-69.15277777777777,71.8125,94.6861111111111,68.08888888888889,191.5 +94.73555555555555,-69.18888888888888,71.85,94.73555555555555,68.12444444444445,191.60000000000002 +94.785,-69.225,71.8875,94.785,68.16,191.70000000000002 +94.83444444444444,-69.2611111111111,71.925,94.83444444444444,68.19555555555556,191.8 +94.88388888888889,-69.29722222222222,71.96249999999999,94.88388888888889,68.2311111111111,191.9 +94.93333333333334,-69.33333333333333,72.0,94.93333333333334,68.26666666666667,192.0 +94.98277777777777,-69.36944444444444,72.0375,94.98277777777777,68.30222222222223,192.10000000000002 +95.03222222222222,-69.40555555555555,72.075,95.03222222222222,68.33777777777777,192.20000000000002 +95.08166666666666,-69.44166666666666,72.1125,95.08166666666666,68.37333333333333,192.3 +95.13111111111111,-69.47777777777777,72.14999999999999,95.13111111111111,68.40888888888888,192.4 +95.18055555555556,-69.51388888888889,72.1875,95.18055555555556,68.44444444444444,192.5 +95.23,-69.55,72.225,95.23,68.48,192.60000000000002 +95.27944444444444,-69.58611111111111,72.2625,95.27944444444444,68.51555555555555,192.70000000000002 +95.32888888888888,-69.62222222222222,72.3,95.32888888888888,68.55111111111111,192.8 +95.37833333333333,-69.65833333333333,72.33749999999999,95.37833333333333,68.58666666666667,192.9 +95.42777777777778,-69.69444444444444,72.375,95.42777777777778,68.62222222222222,193.0 +95.47722222222222,-69.73055555555555,72.4125,95.47722222222222,68.65777777777778,193.10000000000002 +95.52666666666667,-69.76666666666667,72.45,95.52666666666667,68.69333333333333,193.20000000000002 +95.5761111111111,-69.80277777777778,72.4875,95.5761111111111,68.72888888888889,193.3 +95.62555555555555,-69.83888888888889,72.52499999999999,95.62555555555555,68.76444444444445,193.4 +95.675,-69.875,72.5625,95.675,68.8,193.5 +95.72444444444444,-69.91111111111111,72.6,95.72444444444444,68.83555555555556,193.60000000000002 +95.77388888888889,-69.94722222222221,72.6375,95.77388888888889,68.8711111111111,193.70000000000002 +95.82333333333334,-69.98333333333332,72.675,95.82333333333334,68.90666666666667,193.8 +95.87277777777777,-70.01944444444443,72.71249999999999,95.87277777777777,68.94222222222223,193.9 +95.92222222222222,-70.05555555555554,72.75,95.92222222222222,68.97777777777777,194.0 +95.97166666666666,-70.09166666666665,72.7875,95.97166666666666,69.01333333333334,194.10000000000002 +96.02111111111111,-70.12777777777777,72.825,96.02111111111111,69.04888888888888,194.20000000000002 +96.07055555555556,-70.16388888888888,72.8625,96.07055555555556,69.08444444444444,194.3 +96.12,-70.19999999999999,72.89999999999999,96.12,69.12,194.4 +96.16944444444444,-70.2361111111111,72.9375,96.16944444444444,69.15555555555555,194.5 +96.21888888888888,-70.27222222222221,72.975,96.21888888888888,69.19111111111111,194.60000000000002 +96.26833333333333,-70.30833333333332,73.0125,96.26833333333333,69.22666666666667,194.70000000000002 +96.31777777777778,-70.34444444444443,73.05,96.31777777777778,69.26222222222222,194.8 +96.36722222222222,-70.38055555555555,73.08749999999999,96.36722222222222,69.29777777777778,194.9 +96.41666666666667,-70.41666666666666,73.125,96.41666666666667,69.33333333333333,195.0 +96.4661111111111,-70.45277777777777,73.1625,96.4661111111111,69.36888888888889,195.10000000000002 +96.51555555555555,-70.48888888888888,73.2,96.51555555555555,69.40444444444445,195.20000000000002 +96.565,-70.52499999999999,73.2375,96.565,69.44,195.3 +96.61444444444444,-70.5611111111111,73.27499999999999,96.61444444444444,69.47555555555556,195.4 +96.66388888888889,-70.59722222222221,73.3125,96.66388888888889,69.5111111111111,195.5 +96.71333333333334,-70.63333333333333,73.35,96.71333333333334,69.54666666666667,195.60000000000002 +96.76277777777777,-70.66944444444444,73.3875,96.76277777777777,69.58222222222223,195.70000000000002 +96.81222222222222,-70.70555555555555,73.425,96.81222222222222,69.61777777777777,195.8 +96.86166666666666,-70.74166666666666,73.46249999999999,96.86166666666666,69.65333333333334,195.9 +96.91111111111111,-70.77777777777777,73.5,96.91111111111111,69.68888888888888,196.0 +96.96055555555556,-70.81388888888888,73.5375,96.96055555555556,69.72444444444444,196.10000000000002 +97.01,-70.85,73.575,97.01,69.76,196.20000000000002 +97.05944444444444,-70.8861111111111,73.6125,97.05944444444444,69.79555555555555,196.3 +97.10888888888888,-70.92222222222222,73.64999999999999,97.10888888888888,69.83111111111111,196.4 +97.15833333333333,-70.95833333333333,73.6875,97.15833333333333,69.86666666666666,196.5 +97.20777777777778,-70.99444444444444,73.725,97.20777777777778,69.90222222222222,196.60000000000002 +97.25722222222223,-71.03055555555555,73.7625,97.25722222222223,69.93777777777778,196.70000000000002 +97.30666666666667,-71.06666666666666,73.8,97.30666666666667,69.97333333333333,196.8 +97.3561111111111,-71.10277777777777,73.83749999999999,97.3561111111111,70.00888888888889,196.9 +97.40555555555555,-71.13888888888889,73.875,97.40555555555555,70.04444444444445,197.0 +97.455,-71.175,73.9125,97.455,70.08,197.10000000000002 +97.50444444444445,-71.21111111111111,73.95,97.50444444444445,70.11555555555556,197.20000000000002 +97.55388888888889,-71.24722222222222,73.9875,97.55388888888889,70.1511111111111,197.3 +97.60333333333334,-71.28333333333333,74.02499999999999,97.60333333333334,70.18666666666667,197.4 +97.65277777777777,-71.31944444444444,74.0625,97.65277777777777,70.22222222222223,197.5 +97.70222222222222,-71.35555555555555,74.1,97.70222222222222,70.25777777777778,197.60000000000002 +97.75166666666667,-71.39166666666667,74.1375,97.75166666666667,70.29333333333334,197.70000000000002 +97.80111111111111,-71.42777777777778,74.175,97.80111111111111,70.32888888888888,197.8 +97.85055555555556,-71.46388888888889,74.21249999999999,97.85055555555556,70.36444444444444,197.9 +97.89999999999999,-71.5,74.25,97.89999999999999,70.4,198.0 +97.94944444444444,-71.53611111111111,74.2875,97.94944444444444,70.43555555555555,198.10000000000002 +97.99888888888889,-71.57222222222221,74.325,97.99888888888889,70.47111111111111,198.20000000000002 +98.04833333333333,-71.60833333333332,74.3625,98.04833333333333,70.50666666666666,198.3 +98.09777777777778,-71.64444444444443,74.39999999999999,98.09777777777778,70.54222222222222,198.4 +98.14722222222223,-71.68055555555554,74.4375,98.14722222222223,70.57777777777778,198.5 +98.19666666666666,-71.71666666666665,74.475,98.19666666666666,70.61333333333333,198.60000000000002 +98.2461111111111,-71.75277777777777,74.5125,98.2461111111111,70.64888888888889,198.70000000000002 +98.29555555555555,-71.78888888888888,74.55,98.29555555555555,70.68444444444444,198.8 +98.345,-71.82499999999999,74.58749999999999,98.345,70.72,198.9 +98.39444444444445,-71.8611111111111,74.625,98.39444444444445,70.75555555555556,199.0 +98.44388888888889,-71.89722222222221,74.6625,98.44388888888889,70.7911111111111,199.10000000000002 +98.49333333333333,-71.93333333333332,74.7,98.49333333333333,70.82666666666667,199.20000000000002 +98.54277777777777,-71.96944444444443,74.7375,98.54277777777777,70.86222222222223,199.3 +98.59222222222222,-72.00555555555555,74.77499999999999,98.59222222222222,70.89777777777778,199.4 +98.64166666666667,-72.04166666666666,74.8125,98.64166666666667,70.93333333333334,199.5 +98.69111111111111,-72.07777777777777,74.85,98.69111111111111,70.96888888888888,199.60000000000002 +98.74055555555556,-72.11388888888888,74.8875,98.74055555555556,71.00444444444445,199.70000000000002 +98.78999999999999,-72.14999999999999,74.925,98.78999999999999,71.04,199.8 +98.83944444444444,-72.1861111111111,74.96249999999999,98.83944444444444,71.07555555555555,199.9 +98.88888888888889,-72.22222222222221,75.0,98.88888888888889,71.11111111111111,200.0 +98.93833333333333,-72.25833333333333,75.0375,98.93833333333333,71.14666666666666,200.10000000000002 +98.98777777777778,-72.29444444444444,75.075,98.98777777777778,71.18222222222222,200.20000000000002 +99.03722222222223,-72.33055555555555,75.1125,99.03722222222223,71.21777777777778,200.3 +99.08666666666666,-72.36666666666666,75.14999999999999,99.08666666666666,71.25333333333333,200.4 +99.1361111111111,-72.40277777777777,75.1875,99.1361111111111,71.28888888888889,200.5 +99.18555555555555,-72.43888888888888,75.225,99.18555555555555,71.32444444444444,200.60000000000002 +99.235,-72.475,75.2625,99.235,71.36,200.70000000000002 +99.28444444444445,-72.5111111111111,75.3,99.28444444444445,71.39555555555556,200.8 +99.3338888888889,-72.54722222222222,75.33749999999999,99.3338888888889,71.43111111111111,200.9 +99.38333333333333,-72.58333333333333,75.375,99.38333333333333,71.46666666666667,201.0 +99.43277777777777,-72.61944444444444,75.4125,99.43277777777777,71.50222222222222,201.10000000000002 +99.48222222222222,-72.65555555555555,75.45,99.48222222222222,71.53777777777778,201.20000000000002 +99.53166666666667,-72.69166666666666,75.4875,99.53166666666667,71.57333333333334,201.3 +99.58111111111111,-72.72777777777777,75.52499999999999,99.58111111111111,71.60888888888888,201.4 +99.63055555555556,-72.76388888888889,75.5625,99.63055555555556,71.64444444444445,201.5 +99.67999999999999,-72.8,75.6,99.67999999999999,71.68,201.60000000000002 +99.72944444444444,-72.83611111111111,75.6375,99.72944444444444,71.71555555555555,201.70000000000002 +99.77888888888889,-72.87222222222222,75.675,99.77888888888889,71.75111111111111,201.8 +99.82833333333333,-72.90833333333333,75.71249999999999,99.82833333333333,71.78666666666666,201.9 +99.87777777777778,-72.94444444444444,75.75,99.87777777777778,71.82222222222222,202.0 +99.92722222222223,-72.98055555555555,75.7875,99.92722222222223,71.85777777777778,202.10000000000002 +99.97666666666666,-73.01666666666667,75.825,99.97666666666666,71.89333333333333,202.20000000000002 +100.0261111111111,-73.05277777777778,75.8625,100.0261111111111,71.92888888888889,202.3 +100.07555555555555,-73.08888888888889,75.89999999999999,100.07555555555555,71.96444444444444,202.4 +100.125,-73.125,75.9375,100.125,72.0,202.5 +100.17444444444445,-73.1611111111111,75.975,100.17444444444445,72.03555555555556,202.60000000000002 +100.2238888888889,-73.19722222222221,76.0125,100.2238888888889,72.07111111111111,202.70000000000002 +100.27333333333333,-73.23333333333332,76.05,100.27333333333333,72.10666666666667,202.8 +100.32277777777777,-73.26944444444443,76.08749999999999,100.32277777777777,72.14222222222222,202.9 +100.37222222222222,-73.30555555555554,76.125,100.37222222222222,72.17777777777778,203.0 +100.42166666666667,-73.34166666666665,76.1625,100.42166666666667,72.21333333333334,203.10000000000002 +100.47111111111111,-73.37777777777777,76.2,100.47111111111111,72.24888888888889,203.20000000000002 +100.52055555555556,-73.41388888888888,76.2375,100.52055555555556,72.28444444444445,203.3 +100.57,-73.44999999999999,76.27499999999999,100.57,72.32,203.4 +100.61944444444444,-73.4861111111111,76.3125,100.61944444444444,72.35555555555555,203.5 +100.66888888888889,-73.52222222222221,76.35,100.66888888888889,72.39111111111112,203.60000000000002 +100.71833333333333,-73.55833333333332,76.3875,100.71833333333333,72.42666666666666,203.70000000000002 +100.76777777777778,-73.59444444444443,76.425,100.76777777777778,72.46222222222222,203.8 +100.81722222222223,-73.63055555555555,76.46249999999999,100.81722222222223,72.49777777777778,203.9 +100.86666666666666,-73.66666666666666,76.5,100.86666666666666,72.53333333333333,204.0 +100.9161111111111,-73.70277777777777,76.5375,100.9161111111111,72.56888888888889,204.10000000000002 +100.96555555555555,-73.73888888888888,76.575,100.96555555555555,72.60444444444444,204.20000000000002 +101.015,-73.77499999999999,76.6125,101.015,72.64,204.3 +101.06444444444445,-73.8111111111111,76.64999999999999,101.06444444444445,72.67555555555556,204.4 +101.1138888888889,-73.84722222222221,76.6875,101.1138888888889,72.71111111111111,204.5 +101.16333333333333,-73.88333333333333,76.725,101.16333333333333,72.74666666666667,204.60000000000002 +101.21277777777777,-73.91944444444444,76.7625,101.21277777777777,72.78222222222222,204.70000000000002 +101.26222222222222,-73.95555555555555,76.8,101.26222222222222,72.81777777777778,204.8 +101.31166666666667,-73.99166666666666,76.83749999999999,101.31166666666667,72.85333333333334,204.9 +101.36111111111111,-74.02777777777777,76.875,101.36111111111111,72.88888888888889,205.0 +101.41055555555555,-74.06388888888888,76.9125,101.41055555555555,72.92444444444445,205.10000000000002 +101.46,-74.1,76.95,101.46,72.96,205.20000000000002 +101.50944444444444,-74.1361111111111,76.9875,101.50944444444444,72.99555555555555,205.3 +101.55888888888889,-74.17222222222222,77.02499999999999,101.55888888888889,73.03111111111112,205.4 +101.60833333333333,-74.20833333333333,77.0625,101.60833333333333,73.06666666666666,205.5 +101.65777777777778,-74.24444444444444,77.1,101.65777777777778,73.10222222222222,205.60000000000002 +101.70722222222221,-74.28055555555555,77.1375,101.70722222222221,73.13777777777777,205.70000000000002 +101.75666666666666,-74.31666666666666,77.175,101.75666666666666,73.17333333333333,205.8 +101.80611111111111,-74.35277777777777,77.21249999999999,101.80611111111111,73.2088888888889,205.9 +101.85555555555555,-74.38888888888889,77.25,101.85555555555555,73.24444444444444,206.0 +101.905,-74.425,77.2875,101.905,73.28,206.10000000000002 +101.95444444444445,-74.46111111111111,77.325,101.95444444444445,73.31555555555556,206.20000000000002 +102.00388888888888,-74.49722222222222,77.3625,102.00388888888888,73.35111111111111,206.3 +102.05333333333333,-74.53333333333333,77.39999999999999,102.05333333333333,73.38666666666667,206.4 +102.10277777777777,-74.56944444444444,77.4375,102.10277777777777,73.42222222222222,206.5 +102.15222222222222,-74.60555555555555,77.475,102.15222222222222,73.45777777777778,206.60000000000002 +102.20166666666667,-74.64166666666667,77.5125,102.20166666666667,73.49333333333334,206.70000000000002 +102.25111111111111,-74.67777777777778,77.55,102.25111111111111,73.52888888888889,206.8 +102.30055555555555,-74.71388888888889,77.58749999999999,102.30055555555555,73.56444444444445,206.9 +102.35,-74.75,77.625,102.35,73.6,207.0 +102.39944444444444,-74.7861111111111,77.6625,102.39944444444444,73.63555555555556,207.10000000000002 +102.44888888888889,-74.82222222222221,77.7,102.44888888888889,73.67111111111112,207.20000000000002 +102.49833333333333,-74.85833333333332,77.7375,102.49833333333333,73.70666666666666,207.3 +102.54777777777778,-74.89444444444443,77.77499999999999,102.54777777777778,73.74222222222222,207.4 +102.59722222222221,-74.93055555555554,77.8125,102.59722222222221,73.77777777777777,207.5 +102.64666666666666,-74.96666666666665,77.85,102.64666666666666,73.81333333333333,207.60000000000002 +102.69611111111111,-75.00277777777777,77.8875,102.69611111111111,73.8488888888889,207.70000000000002 +102.74555555555555,-75.03888888888888,77.925,102.74555555555555,73.88444444444444,207.8 +102.795,-75.07499999999999,77.96249999999999,102.795,73.92,207.9 +102.84444444444445,-75.1111111111111,78.0,102.84444444444445,73.95555555555555,208.0 +102.89388888888888,-75.14722222222221,78.0375,102.89388888888888,73.99111111111111,208.10000000000002 +102.94333333333333,-75.18333333333332,78.075,102.94333333333333,74.02666666666667,208.20000000000002 +102.99277777777777,-75.21944444444443,78.1125,102.99277777777777,74.06222222222222,208.3 +103.04222222222222,-75.25555555555555,78.14999999999999,103.04222222222222,74.09777777777778,208.4 +103.09166666666667,-75.29166666666666,78.1875,103.09166666666667,74.13333333333334,208.5 +103.14111111111112,-75.32777777777777,78.225,103.14111111111112,74.16888888888889,208.60000000000002 +103.19055555555555,-75.36388888888888,78.2625,103.19055555555555,74.20444444444445,208.70000000000002 +103.24,-75.39999999999999,78.3,103.24,74.24,208.8 +103.28944444444444,-75.4361111111111,78.33749999999999,103.28944444444444,74.27555555555556,208.9 +103.33888888888889,-75.47222222222221,78.375,103.33888888888889,74.31111111111112,209.0 +103.38833333333334,-75.50833333333333,78.4125,103.38833333333334,74.34666666666666,209.10000000000002 +103.43777777777778,-75.54444444444444,78.45,103.43777777777778,74.38222222222223,209.20000000000002 +103.48722222222221,-75.58055555555555,78.4875,103.48722222222221,74.41777777777777,209.3 +103.53666666666666,-75.61666666666666,78.52499999999999,103.53666666666666,74.45333333333333,209.4 +103.58611111111111,-75.65277777777777,78.5625,103.58611111111111,74.4888888888889,209.5 +103.63555555555556,-75.68888888888888,78.6,103.63555555555556,74.52444444444444,209.60000000000002 +103.685,-75.725,78.6375,103.685,74.56,209.70000000000002 +103.73444444444445,-75.7611111111111,78.675,103.73444444444445,74.59555555555555,209.8 +103.78388888888888,-75.79722222222222,78.71249999999999,103.78388888888888,74.63111111111111,209.9 +103.83333333333333,-75.83333333333333,78.75,103.83333333333333,74.66666666666667,210.0 +103.88277777777778,-75.86944444444444,78.7875,103.88277777777778,74.70222222222222,210.10000000000002 +103.93222222222222,-75.90555555555555,78.825,103.93222222222222,74.73777777777778,210.20000000000002 +103.98166666666667,-75.94166666666666,78.8625,103.98166666666667,74.77333333333333,210.3 +104.03111111111112,-75.97777777777777,78.89999999999999,104.03111111111112,74.80888888888889,210.4 +104.08055555555555,-76.01388888888889,78.9375,104.08055555555555,74.84444444444445,210.5 +104.13,-76.05,78.975,104.13,74.88,210.60000000000002 +104.17944444444444,-76.08611111111111,79.0125,104.17944444444444,74.91555555555556,210.70000000000002 +104.22888888888889,-76.12222222222222,79.05,104.22888888888889,74.95111111111112,210.8 +104.27833333333334,-76.15833333333333,79.08749999999999,104.27833333333334,74.98666666666666,210.9 +104.32777777777778,-76.19444444444444,79.125,104.32777777777778,75.02222222222223,211.0 +104.37722222222222,-76.23055555555555,79.1625,104.37722222222222,75.05777777777777,211.10000000000002 +104.42666666666666,-76.26666666666667,79.2,104.42666666666666,75.09333333333333,211.20000000000002 +104.47611111111111,-76.30277777777778,79.2375,104.47611111111111,75.1288888888889,211.3 +104.52555555555556,-76.33888888888889,79.27499999999999,104.52555555555556,75.16444444444444,211.4 +104.575,-76.37499999999999,79.3125,104.575,75.2,211.5 +104.62444444444445,-76.4111111111111,79.35,104.62444444444445,75.23555555555555,211.60000000000002 +104.67388888888888,-76.44722222222221,79.3875,104.67388888888888,75.27111111111111,211.70000000000002 +104.72333333333333,-76.48333333333332,79.425,104.72333333333333,75.30666666666667,211.8 +104.77277777777778,-76.51944444444443,79.46249999999999,104.77277777777778,75.34222222222222,211.9 +104.82222222222222,-76.55555555555554,79.5,104.82222222222222,75.37777777777778,212.0 +104.87166666666667,-76.59166666666665,79.5375,104.87166666666667,75.41333333333333,212.10000000000002 +104.9211111111111,-76.62777777777777,79.575,104.9211111111111,75.44888888888889,212.20000000000002 +104.97055555555555,-76.66388888888888,79.6125,104.97055555555555,75.48444444444445,212.3 +105.02,-76.69999999999999,79.64999999999999,105.02,75.52,212.4 +105.06944444444444,-76.7361111111111,79.6875,105.06944444444444,75.55555555555556,212.5 +105.11888888888889,-76.77222222222221,79.725,105.11888888888889,75.5911111111111,212.60000000000002 +105.16833333333334,-76.80833333333332,79.7625,105.16833333333334,75.62666666666667,212.70000000000002 +105.21777777777777,-76.84444444444443,79.8,105.21777777777777,75.66222222222223,212.8 +105.26722222222222,-76.88055555555555,79.83749999999999,105.26722222222222,75.69777777777777,212.9 +105.31666666666666,-76.91666666666666,79.875,105.31666666666666,75.73333333333333,213.0 +105.36611111111111,-76.95277777777777,79.9125,105.36611111111111,75.7688888888889,213.10000000000002 +105.41555555555556,-76.98888888888888,79.95,105.41555555555556,75.80444444444444,213.20000000000002 +105.465,-77.02499999999999,79.9875,105.465,75.84,213.3 +105.51444444444444,-77.0611111111111,80.02499999999999,105.51444444444444,75.87555555555555,213.4 +105.56388888888888,-77.09722222222221,80.0625,105.56388888888888,75.91111111111111,213.5 +105.61333333333333,-77.13333333333333,80.1,105.61333333333333,75.94666666666667,213.60000000000002 +105.66277777777778,-77.16944444444444,80.1375,105.66277777777778,75.98222222222222,213.70000000000002 +105.71222222222222,-77.20555555555555,80.175,105.71222222222222,76.01777777777778,213.8 +105.76166666666667,-77.24166666666666,80.21249999999999,105.76166666666667,76.05333333333333,213.9 +105.8111111111111,-77.27777777777777,80.25,105.8111111111111,76.08888888888889,214.0 +105.86055555555555,-77.31388888888888,80.2875,105.86055555555555,76.12444444444445,214.10000000000002 +105.91,-77.35,80.325,105.91,76.16,214.20000000000002 +105.95944444444444,-77.3861111111111,80.3625,105.95944444444444,76.19555555555556,214.3 +106.00888888888889,-77.42222222222222,80.39999999999999,106.00888888888889,76.2311111111111,214.4 +106.05833333333334,-77.45833333333333,80.4375,106.05833333333334,76.26666666666667,214.5 +106.10777777777777,-77.49444444444444,80.475,106.10777777777777,76.30222222222223,214.60000000000002 +106.15722222222222,-77.53055555555555,80.5125,106.15722222222222,76.33777777777777,214.70000000000002 +106.20666666666666,-77.56666666666666,80.55,106.20666666666666,76.37333333333333,214.8 +106.25611111111111,-77.60277777777777,80.58749999999999,106.25611111111111,76.40888888888888,214.9 +106.30555555555556,-77.63888888888889,80.625,106.30555555555556,76.44444444444444,215.0 +106.355,-77.675,80.6625,106.355,76.48,215.10000000000002 +106.40444444444444,-77.71111111111111,80.7,106.40444444444444,76.51555555555555,215.20000000000002 +106.45388888888888,-77.74722222222222,80.7375,106.45388888888888,76.55111111111111,215.3 +106.50333333333333,-77.78333333333333,80.77499999999999,106.50333333333333,76.58666666666667,215.4 +106.55277777777778,-77.81944444444444,80.8125,106.55277777777778,76.62222222222222,215.5 +106.60222222222222,-77.85555555555555,80.85,106.60222222222222,76.65777777777778,215.60000000000002 +106.65166666666667,-77.89166666666667,80.8875,106.65166666666667,76.69333333333333,215.70000000000002 +106.7011111111111,-77.92777777777778,80.925,106.7011111111111,76.72888888888889,215.8 +106.75055555555555,-77.96388888888889,80.96249999999999,106.75055555555555,76.76444444444445,215.9 +106.8,-77.99999999999999,81.0,106.8,76.8,216.0 +106.84944444444444,-78.0361111111111,81.0375,106.84944444444444,76.83555555555556,216.10000000000002 +106.89888888888889,-78.07222222222221,81.075,106.89888888888889,76.8711111111111,216.20000000000002 +106.94833333333334,-78.10833333333332,81.1125,106.94833333333334,76.90666666666667,216.3 +106.99777777777777,-78.14444444444443,81.14999999999999,106.99777777777777,76.94222222222223,216.4 +107.04722222222222,-78.18055555555554,81.1875,107.04722222222222,76.97777777777777,216.5 +107.09666666666666,-78.21666666666665,81.225,107.09666666666666,77.01333333333334,216.60000000000002 +107.14611111111111,-78.25277777777777,81.2625,107.14611111111111,77.04888888888888,216.70000000000002 +107.19555555555556,-78.28888888888888,81.3,107.19555555555556,77.08444444444444,216.8 +107.245,-78.32499999999999,81.33749999999999,107.245,77.12,216.9 +107.29444444444444,-78.3611111111111,81.375,107.29444444444444,77.15555555555555,217.0 +107.34388888888888,-78.39722222222221,81.4125,107.34388888888888,77.19111111111111,217.10000000000002 +107.39333333333333,-78.43333333333332,81.45,107.39333333333333,77.22666666666667,217.20000000000002 +107.44277777777778,-78.46944444444443,81.4875,107.44277777777778,77.26222222222222,217.3 +107.49222222222222,-78.50555555555555,81.52499999999999,107.49222222222222,77.29777777777778,217.4 +107.54166666666667,-78.54166666666666,81.5625,107.54166666666667,77.33333333333333,217.5 +107.5911111111111,-78.57777777777777,81.6,107.5911111111111,77.36888888888889,217.60000000000002 +107.64055555555555,-78.61388888888888,81.6375,107.64055555555555,77.40444444444445,217.70000000000002 +107.69,-78.64999999999999,81.675,107.69,77.44,217.8 +107.73944444444444,-78.6861111111111,81.71249999999999,107.73944444444444,77.47555555555556,217.9 +107.78888888888889,-78.72222222222221,81.75,107.78888888888889,77.5111111111111,218.0 +107.83833333333334,-78.75833333333333,81.7875,107.83833333333334,77.54666666666667,218.10000000000002 +107.88777777777777,-78.79444444444444,81.825,107.88777777777777,77.58222222222223,218.20000000000002 +107.93722222222222,-78.83055555555555,81.8625,107.93722222222222,77.61777777777777,218.3 +107.98666666666666,-78.86666666666666,81.89999999999999,107.98666666666666,77.65333333333334,218.4 +108.03611111111111,-78.90277777777777,81.9375,108.03611111111111,77.68888888888888,218.5 +108.08555555555556,-78.93888888888888,81.975,108.08555555555556,77.72444444444444,218.60000000000002 +108.135,-78.975,82.0125,108.135,77.76,218.70000000000002 +108.18444444444444,-79.0111111111111,82.05,108.18444444444444,77.79555555555555,218.8 +108.23388888888888,-79.04722222222222,82.08749999999999,108.23388888888888,77.83111111111111,218.9 +108.28333333333333,-79.08333333333333,82.125,108.28333333333333,77.86666666666666,219.0 +108.33277777777778,-79.11944444444444,82.1625,108.33277777777778,77.90222222222222,219.10000000000002 +108.38222222222223,-79.15555555555555,82.2,108.38222222222223,77.93777777777778,219.20000000000002 +108.43166666666667,-79.19166666666666,82.2375,108.43166666666667,77.97333333333333,219.3 +108.4811111111111,-79.22777777777777,82.27499999999999,108.4811111111111,78.00888888888889,219.4 +108.53055555555555,-79.26388888888889,82.3125,108.53055555555555,78.04444444444445,219.5 +108.58,-79.3,82.35,108.58,78.08,219.60000000000002 +108.62944444444445,-79.33611111111111,82.3875,108.62944444444445,78.11555555555556,219.70000000000002 +108.67888888888889,-79.37222222222222,82.425,108.67888888888889,78.1511111111111,219.8 +108.72833333333332,-79.40833333333333,82.46249999999999,108.72833333333332,78.18666666666667,219.9 +108.77777777777777,-79.44444444444444,82.5,108.77777777777777,78.22222222222223,220.0 +108.82722222222222,-79.48055555555555,82.5375,108.82722222222222,78.25777777777778,220.10000000000002 +108.87666666666667,-79.51666666666667,82.575,108.87666666666667,78.29333333333334,220.20000000000002 +108.92611111111111,-79.55277777777778,82.6125,108.92611111111111,78.32888888888888,220.3 +108.97555555555556,-79.58888888888887,82.64999999999999,108.97555555555556,78.36444444444444,220.4 +109.02499999999999,-79.62499999999999,82.6875,109.02499999999999,78.4,220.5 +109.07444444444444,-79.6611111111111,82.725,109.07444444444444,78.43555555555555,220.60000000000002 +109.12388888888889,-79.69722222222221,82.7625,109.12388888888889,78.47111111111111,220.70000000000002 +109.17333333333333,-79.73333333333332,82.8,109.17333333333333,78.50666666666666,220.8 +109.22277777777778,-79.76944444444443,82.83749999999999,109.22277777777778,78.54222222222222,220.9 +109.27222222222223,-79.80555555555554,82.875,109.27222222222223,78.57777777777778,221.0 +109.32166666666666,-79.84166666666665,82.9125,109.32166666666666,78.61333333333333,221.10000000000002 +109.3711111111111,-79.87777777777777,82.95,109.3711111111111,78.64888888888889,221.20000000000002 +109.42055555555555,-79.91388888888888,82.9875,109.42055555555555,78.68444444444444,221.3 +109.47,-79.94999999999999,83.02499999999999,109.47,78.72,221.4 +109.51944444444445,-79.9861111111111,83.0625,109.51944444444445,78.75555555555556,221.5 +109.56888888888889,-80.02222222222221,83.1,109.56888888888889,78.7911111111111,221.60000000000002 +109.61833333333333,-80.05833333333332,83.1375,109.61833333333333,78.82666666666667,221.70000000000002 +109.66777777777777,-80.09444444444443,83.175,109.66777777777777,78.86222222222223,221.8 +109.71722222222222,-80.13055555555555,83.21249999999999,109.71722222222222,78.89777777777778,221.9 +109.76666666666667,-80.16666666666666,83.25,109.76666666666667,78.93333333333334,222.0 +109.81611111111111,-80.20277777777777,83.2875,109.81611111111111,78.96888888888888,222.10000000000002 +109.86555555555556,-80.23888888888888,83.325,109.86555555555556,79.00444444444445,222.20000000000002 +109.91499999999999,-80.27499999999999,83.3625,109.91499999999999,79.04,222.3 +109.96444444444444,-80.3111111111111,83.39999999999999,109.96444444444444,79.07555555555555,222.4 +110.01388888888889,-80.34722222222221,83.4375,110.01388888888889,79.11111111111111,222.5 +110.06333333333333,-80.38333333333333,83.475,110.06333333333333,79.14666666666666,222.60000000000002 +110.11277777777778,-80.41944444444444,83.5125,110.11277777777778,79.18222222222222,222.70000000000002 +110.16222222222223,-80.45555555555555,83.55,110.16222222222223,79.21777777777778,222.8 +110.21166666666666,-80.49166666666666,83.58749999999999,110.21166666666666,79.25333333333333,222.9 +110.2611111111111,-80.52777777777777,83.625,110.2611111111111,79.28888888888889,223.0 +110.31055555555555,-80.56388888888888,83.6625,110.31055555555555,79.32444444444444,223.10000000000002 +110.36,-80.6,83.7,110.36,79.36,223.20000000000002 +110.40944444444445,-80.6361111111111,83.7375,110.40944444444445,79.39555555555556,223.3 +110.4588888888889,-80.67222222222222,83.77499999999999,110.4588888888889,79.43111111111111,223.4 +110.50833333333333,-80.70833333333333,83.8125,110.50833333333333,79.46666666666667,223.5 +110.55777777777777,-80.74444444444444,83.85,110.55777777777777,79.50222222222222,223.60000000000002 +110.60722222222222,-80.78055555555555,83.8875,110.60722222222222,79.53777777777778,223.70000000000002 +110.65666666666667,-80.81666666666666,83.925,110.65666666666667,79.57333333333334,223.8 +110.70611111111111,-80.85277777777777,83.96249999999999,110.70611111111111,79.60888888888888,223.9 +110.75555555555556,-80.88888888888889,84.0,110.75555555555556,79.64444444444445,224.0 +110.80499999999999,-80.925,84.0375,110.80499999999999,79.68,224.10000000000002 +110.85444444444444,-80.96111111111111,84.075,110.85444444444444,79.71555555555555,224.20000000000002 +110.90388888888889,-80.99722222222222,84.1125,110.90388888888889,79.75111111111111,224.3 +110.95333333333333,-81.03333333333333,84.14999999999999,110.95333333333333,79.78666666666666,224.4 +111.00277777777778,-81.06944444444444,84.1875,111.00277777777778,79.82222222222222,224.5 +111.05222222222223,-81.10555555555555,84.225,111.05222222222223,79.85777777777778,224.60000000000002 +111.10166666666666,-81.14166666666667,84.2625,111.10166666666666,79.89333333333333,224.70000000000002 +111.1511111111111,-81.17777777777778,84.3,111.1511111111111,79.92888888888889,224.8 +111.20055555555555,-81.21388888888887,84.33749999999999,111.20055555555555,79.96444444444444,224.9 +111.25,-81.24999999999999,84.375,111.25,80.0,225.0 +111.29944444444445,-81.2861111111111,84.4125,111.29944444444445,80.03555555555556,225.10000000000002 +111.3488888888889,-81.32222222222221,84.45,111.3488888888889,80.07111111111111,225.20000000000002 +111.39833333333333,-81.35833333333332,84.4875,111.39833333333333,80.10666666666667,225.3 +111.44777777777777,-81.39444444444443,84.52499999999999,111.44777777777777,80.14222222222222,225.4 +111.49722222222222,-81.43055555555554,84.5625,111.49722222222222,80.17777777777778,225.5 +111.54666666666667,-81.46666666666665,84.6,111.54666666666667,80.21333333333334,225.60000000000002 +111.59611111111111,-81.50277777777777,84.6375,111.59611111111111,80.24888888888889,225.70000000000002 +111.64555555555556,-81.53888888888888,84.675,111.64555555555556,80.28444444444445,225.8 +111.695,-81.57499999999999,84.71249999999999,111.695,80.32,225.9 +111.74444444444444,-81.6111111111111,84.75,111.74444444444444,80.35555555555555,226.0 +111.79388888888889,-81.64722222222221,84.7875,111.79388888888889,80.39111111111112,226.10000000000002 +111.84333333333333,-81.68333333333332,84.825,111.84333333333333,80.42666666666666,226.20000000000002 +111.89277777777778,-81.71944444444443,84.8625,111.89277777777778,80.46222222222222,226.3 +111.94222222222223,-81.75555555555555,84.89999999999999,111.94222222222223,80.49777777777778,226.4 +111.99166666666666,-81.79166666666666,84.9375,111.99166666666666,80.53333333333333,226.5 +112.0411111111111,-81.82777777777777,84.975,112.0411111111111,80.56888888888889,226.60000000000002 +112.09055555555555,-81.86388888888888,85.0125,112.09055555555555,80.60444444444444,226.70000000000002 +112.14,-81.89999999999999,85.05,112.14,80.64,226.8 +112.18944444444445,-81.9361111111111,85.08749999999999,112.18944444444445,80.67555555555556,226.9 +112.23888888888888,-81.97222222222221,85.125,112.23888888888888,80.71111111111111,227.0 +112.28833333333333,-82.00833333333333,85.1625,112.28833333333333,80.74666666666667,227.10000000000002 +112.33777777777777,-82.04444444444444,85.2,112.33777777777777,80.78222222222222,227.20000000000002 +112.38722222222222,-82.08055555555555,85.2375,112.38722222222222,80.81777777777778,227.3 +112.43666666666667,-82.11666666666666,85.27499999999999,112.43666666666667,80.85333333333334,227.4 +112.48611111111111,-82.15277777777777,85.3125,112.48611111111111,80.88888888888889,227.5 +112.53555555555555,-82.18888888888888,85.35,112.53555555555555,80.92444444444445,227.60000000000002 +112.585,-82.225,85.3875,112.585,80.96,227.70000000000002 +112.63444444444444,-82.2611111111111,85.425,112.63444444444444,80.99555555555555,227.8 +112.68388888888889,-82.29722222222222,85.46249999999999,112.68388888888889,81.03111111111112,227.9 +112.73333333333333,-82.33333333333333,85.5,112.73333333333333,81.06666666666666,228.0 +112.78277777777778,-82.36944444444444,85.5375,112.78277777777778,81.10222222222222,228.10000000000002 +112.83222222222221,-82.40555555555555,85.575,112.83222222222221,81.13777777777777,228.20000000000002 +112.88166666666666,-82.44166666666666,85.6125,112.88166666666666,81.17333333333333,228.3 +112.93111111111111,-82.47777777777777,85.64999999999999,112.93111111111111,81.2088888888889,228.4 +112.98055555555555,-82.51388888888889,85.6875,112.98055555555555,81.24444444444444,228.5 +113.03,-82.55,85.725,113.03,81.28,228.60000000000002 +113.07944444444445,-82.58611111111111,85.7625,113.07944444444445,81.31555555555556,228.70000000000002 +113.12888888888888,-82.62222222222222,85.8,113.12888888888888,81.35111111111111,228.8 +113.17833333333333,-82.65833333333333,85.83749999999999,113.17833333333333,81.38666666666667,228.9 +113.22777777777777,-82.69444444444444,85.875,113.22777777777777,81.42222222222222,229.0 +113.27722222222222,-82.73055555555555,85.9125,113.27722222222222,81.45777777777778,229.10000000000002 +113.32666666666667,-82.76666666666667,85.95,113.32666666666667,81.49333333333334,229.20000000000002 +113.37611111111111,-82.80277777777776,85.9875,113.37611111111111,81.52888888888889,229.3 +113.42555555555555,-82.83888888888887,86.02499999999999,113.42555555555555,81.56444444444445,229.4 +113.475,-82.87499999999999,86.0625,113.475,81.6,229.5 +113.52444444444444,-82.9111111111111,86.1,113.52444444444444,81.63555555555556,229.60000000000002 +113.57388888888889,-82.94722222222221,86.1375,113.57388888888889,81.67111111111112,229.70000000000002 +113.62333333333333,-82.98333333333332,86.175,113.62333333333333,81.70666666666666,229.8 +113.67277777777778,-83.01944444444443,86.21249999999999,113.67277777777778,81.74222222222222,229.9 +113.72222222222221,-83.05555555555554,86.25,113.72222222222221,81.77777777777777,230.0 +113.77166666666666,-83.09166666666665,86.2875,113.77166666666666,81.81333333333333,230.10000000000002 +113.82111111111111,-83.12777777777777,86.325,113.82111111111111,81.8488888888889,230.20000000000002 +113.87055555555555,-83.16388888888888,86.3625,113.87055555555555,81.88444444444444,230.3 +113.92,-83.19999999999999,86.39999999999999,113.92,81.92,230.4 +113.96944444444445,-83.2361111111111,86.4375,113.96944444444445,81.95555555555555,230.5 +114.01888888888888,-83.27222222222221,86.475,114.01888888888888,81.99111111111111,230.60000000000002 +114.06833333333333,-83.30833333333332,86.5125,114.06833333333333,82.02666666666667,230.70000000000002 +114.11777777777777,-83.34444444444443,86.55,114.11777777777777,82.06222222222222,230.8 +114.16722222222222,-83.38055555555555,86.58749999999999,114.16722222222222,82.09777777777778,230.9 +114.21666666666667,-83.41666666666666,86.625,114.21666666666667,82.13333333333334,231.0 +114.26611111111112,-83.45277777777777,86.6625,114.26611111111112,82.16888888888889,231.10000000000002 +114.31555555555555,-83.48888888888888,86.7,114.31555555555555,82.20444444444445,231.20000000000002 +114.365,-83.52499999999999,86.7375,114.365,82.24,231.3 +114.41444444444444,-83.5611111111111,86.77499999999999,114.41444444444444,82.27555555555556,231.4 +114.46388888888889,-83.59722222222221,86.8125,114.46388888888889,82.31111111111112,231.5 +114.51333333333334,-83.63333333333333,86.85,114.51333333333334,82.34666666666666,231.60000000000002 +114.56277777777778,-83.66944444444444,86.8875,114.56277777777778,82.38222222222223,231.70000000000002 +114.61222222222221,-83.70555555555555,86.925,114.61222222222221,82.41777777777777,231.8 +114.66166666666666,-83.74166666666666,86.96249999999999,114.66166666666666,82.45333333333333,231.9 +114.71111111111111,-83.77777777777777,87.0,114.71111111111111,82.4888888888889,232.0 +114.76055555555556,-83.81388888888888,87.0375,114.76055555555556,82.52444444444444,232.10000000000002 +114.81,-83.85,87.075,114.81,82.56,232.20000000000002 +114.85944444444445,-83.8861111111111,87.1125,114.85944444444445,82.59555555555555,232.3 +114.90888888888888,-83.92222222222222,87.14999999999999,114.90888888888888,82.63111111111111,232.4 +114.95833333333333,-83.95833333333333,87.1875,114.95833333333333,82.66666666666667,232.5 +115.00777777777778,-83.99444444444444,87.225,115.00777777777778,82.70222222222222,232.60000000000002 +115.05722222222222,-84.03055555555555,87.2625,115.05722222222222,82.73777777777778,232.70000000000002 +115.10666666666667,-84.06666666666666,87.3,115.10666666666667,82.77333333333333,232.8 +115.15611111111112,-84.10277777777777,87.33749999999999,115.15611111111112,82.80888888888889,232.9 +115.20555555555555,-84.13888888888889,87.375,115.20555555555555,82.84444444444445,233.0 +115.255,-84.175,87.4125,115.255,82.88,233.10000000000002 +115.30444444444444,-84.21111111111111,87.45,115.30444444444444,82.91555555555556,233.20000000000002 +115.35388888888889,-84.24722222222222,87.4875,115.35388888888889,82.95111111111112,233.3 +115.40333333333334,-84.28333333333333,87.52499999999999,115.40333333333334,82.98666666666666,233.4 +115.45277777777778,-84.31944444444444,87.5625,115.45277777777778,83.02222222222223,233.5 +115.50222222222222,-84.35555555555555,87.6,115.50222222222222,83.05777777777777,233.60000000000002 +115.55166666666666,-84.39166666666667,87.6375,115.55166666666666,83.09333333333333,233.70000000000002 +115.60111111111111,-84.42777777777776,87.675,115.60111111111111,83.1288888888889,233.8 +115.65055555555556,-84.46388888888887,87.71249999999999,115.65055555555556,83.16444444444444,233.9 +115.7,-84.49999999999999,87.75,115.7,83.2,234.0 +115.74944444444444,-84.5361111111111,87.7875,115.74944444444444,83.23555555555555,234.10000000000002 +115.79888888888888,-84.57222222222221,87.825,115.79888888888888,83.27111111111111,234.20000000000002 +115.84833333333333,-84.60833333333332,87.8625,115.84833333333333,83.30666666666667,234.3 +115.89777777777778,-84.64444444444443,87.89999999999999,115.89777777777778,83.34222222222222,234.4 +115.94722222222222,-84.68055555555554,87.9375,115.94722222222222,83.37777777777778,234.5 +115.99666666666667,-84.71666666666665,87.975,115.99666666666667,83.41333333333333,234.60000000000002 +116.0461111111111,-84.75277777777777,88.0125,116.0461111111111,83.44888888888889,234.70000000000002 +116.09555555555555,-84.78888888888888,88.05,116.09555555555555,83.48444444444445,234.8 +116.145,-84.82499999999999,88.08749999999999,116.145,83.52,234.9 +116.19444444444444,-84.8611111111111,88.125,116.19444444444444,83.55555555555556,235.0 +116.24388888888889,-84.89722222222221,88.1625,116.24388888888889,83.5911111111111,235.10000000000002 +116.29333333333334,-84.93333333333332,88.2,116.29333333333334,83.62666666666667,235.20000000000002 +116.34277777777777,-84.96944444444443,88.2375,116.34277777777777,83.66222222222223,235.3 +116.39222222222222,-85.00555555555555,88.27499999999999,116.39222222222222,83.69777777777777,235.4 +116.44166666666666,-85.04166666666666,88.3125,116.44166666666666,83.73333333333333,235.5 +116.49111111111111,-85.07777777777777,88.35,116.49111111111111,83.7688888888889,235.60000000000002 +116.54055555555556,-85.11388888888888,88.3875,116.54055555555556,83.80444444444444,235.70000000000002 +116.59,-85.14999999999999,88.425,116.59,83.84,235.8 +116.63944444444444,-85.1861111111111,88.46249999999999,116.63944444444444,83.87555555555555,235.9 +116.68888888888888,-85.22222222222221,88.5,116.68888888888888,83.91111111111111,236.0 +116.73833333333333,-85.25833333333333,88.5375,116.73833333333333,83.94666666666667,236.10000000000002 +116.78777777777778,-85.29444444444444,88.575,116.78777777777778,83.98222222222222,236.20000000000002 +116.83722222222222,-85.33055555555555,88.6125,116.83722222222222,84.01777777777778,236.3 +116.88666666666667,-85.36666666666666,88.64999999999999,116.88666666666667,84.05333333333333,236.4 +116.9361111111111,-85.40277777777777,88.6875,116.9361111111111,84.08888888888889,236.5 +116.98555555555555,-85.43888888888888,88.725,116.98555555555555,84.12444444444445,236.60000000000002 +117.035,-85.475,88.7625,117.035,84.16,236.70000000000002 +117.08444444444444,-85.5111111111111,88.8,117.08444444444444,84.19555555555556,236.8 +117.13388888888889,-85.54722222222222,88.83749999999999,117.13388888888889,84.2311111111111,236.9 +117.18333333333334,-85.58333333333333,88.875,117.18333333333334,84.26666666666667,237.0 +117.23277777777777,-85.61944444444444,88.9125,117.23277777777777,84.30222222222223,237.10000000000002 +117.28222222222222,-85.65555555555555,88.95,117.28222222222222,84.33777777777777,237.20000000000002 +117.33166666666666,-85.69166666666666,88.9875,117.33166666666666,84.37333333333333,237.3 +117.38111111111111,-85.72777777777777,89.02499999999999,117.38111111111111,84.40888888888888,237.4 +117.43055555555556,-85.76388888888889,89.0625,117.43055555555556,84.44444444444444,237.5 +117.48,-85.8,89.1,117.48,84.48,237.60000000000002 +117.52944444444444,-85.83611111111111,89.1375,117.52944444444444,84.51555555555555,237.70000000000002 +117.57888888888888,-85.87222222222222,89.175,117.57888888888888,84.55111111111111,237.8 +117.62833333333333,-85.90833333333333,89.21249999999999,117.62833333333333,84.58666666666667,237.9 +117.67777777777778,-85.94444444444444,89.25,117.67777777777778,84.62222222222222,238.0 +117.72722222222222,-85.98055555555555,89.2875,117.72722222222222,84.65777777777778,238.10000000000002 +117.77666666666667,-86.01666666666665,89.325,117.77666666666667,84.69333333333333,238.20000000000002 +117.8261111111111,-86.05277777777776,89.3625,117.8261111111111,84.72888888888889,238.3 +117.87555555555555,-86.08888888888887,89.39999999999999,117.87555555555555,84.76444444444445,238.4 +117.925,-86.12499999999999,89.4375,117.925,84.8,238.5 +117.97444444444444,-86.1611111111111,89.475,117.97444444444444,84.83555555555556,238.60000000000002 +118.02388888888889,-86.19722222222221,89.5125,118.02388888888889,84.8711111111111,238.70000000000002 +118.07333333333334,-86.23333333333332,89.55,118.07333333333334,84.90666666666667,238.8 +118.12277777777777,-86.26944444444443,89.58749999999999,118.12277777777777,84.94222222222223,238.9 +118.17222222222222,-86.30555555555554,89.625,118.17222222222222,84.97777777777777,239.0 +118.22166666666666,-86.34166666666665,89.6625,118.22166666666666,85.01333333333334,239.10000000000002 +118.27111111111111,-86.37777777777777,89.7,118.27111111111111,85.04888888888888,239.20000000000002 +118.32055555555556,-86.41388888888888,89.7375,118.32055555555556,85.08444444444444,239.3 +118.37,-86.44999999999999,89.77499999999999,118.37,85.12,239.4 +118.41944444444444,-86.4861111111111,89.8125,118.41944444444444,85.15555555555555,239.5 +118.46888888888888,-86.52222222222221,89.85,118.46888888888888,85.19111111111111,239.60000000000002 +118.51833333333333,-86.55833333333332,89.8875,118.51833333333333,85.22666666666667,239.70000000000002 +118.56777777777778,-86.59444444444443,89.925,118.56777777777778,85.26222222222222,239.8 +118.61722222222222,-86.63055555555555,89.96249999999999,118.61722222222222,85.29777777777778,239.9 +118.66666666666667,-86.66666666666666,90.0,118.66666666666667,85.33333333333333,240.0 +118.7161111111111,-86.70277777777777,90.0375,118.7161111111111,85.36888888888889,240.10000000000002 +118.76555555555555,-86.73888888888888,90.075,118.76555555555555,85.40444444444445,240.20000000000002 +118.815,-86.77499999999999,90.1125,118.815,85.44,240.3 +118.86444444444444,-86.8111111111111,90.14999999999999,118.86444444444444,85.47555555555556,240.4 +118.91388888888889,-86.84722222222221,90.1875,118.91388888888889,85.5111111111111,240.5 +118.96333333333334,-86.88333333333333,90.225,118.96333333333334,85.54666666666667,240.60000000000002 +119.01277777777777,-86.91944444444444,90.2625,119.01277777777777,85.58222222222223,240.70000000000002 +119.06222222222222,-86.95555555555555,90.3,119.06222222222222,85.61777777777777,240.8 +119.11166666666666,-86.99166666666666,90.33749999999999,119.11166666666666,85.65333333333334,240.9 +119.16111111111111,-87.02777777777777,90.375,119.16111111111111,85.68888888888888,241.0 +119.21055555555556,-87.06388888888888,90.4125,119.21055555555556,85.72444444444444,241.10000000000002 +119.26,-87.1,90.45,119.26,85.76,241.20000000000002 +119.30944444444444,-87.1361111111111,90.4875,119.30944444444444,85.79555555555555,241.3 +119.35888888888888,-87.17222222222222,90.52499999999999,119.35888888888888,85.83111111111111,241.4 +119.40833333333333,-87.20833333333333,90.5625,119.40833333333333,85.86666666666666,241.5 +119.45777777777778,-87.24444444444444,90.6,119.45777777777778,85.90222222222222,241.60000000000002 +119.50722222222223,-87.28055555555555,90.6375,119.50722222222223,85.93777777777778,241.70000000000002 +119.55666666666666,-87.31666666666666,90.675,119.55666666666666,85.97333333333333,241.8 +119.6061111111111,-87.35277777777777,90.71249999999999,119.6061111111111,86.00888888888889,241.9 +119.65555555555555,-87.38888888888889,90.75,119.65555555555555,86.04444444444445,242.0 +119.705,-87.425,90.7875,119.705,86.08,242.10000000000002 +119.75444444444445,-87.46111111111111,90.825,119.75444444444445,86.11555555555556,242.20000000000002 +119.80388888888889,-87.49722222222222,90.8625,119.80388888888889,86.1511111111111,242.3 +119.85333333333332,-87.53333333333333,90.89999999999999,119.85333333333332,86.18666666666667,242.4 +119.90277777777777,-87.56944444444444,90.9375,119.90277777777777,86.22222222222223,242.5 +119.95222222222222,-87.60555555555555,90.975,119.95222222222222,86.25777777777778,242.60000000000002 +120.00166666666667,-87.64166666666665,91.0125,120.00166666666667,86.29333333333334,242.70000000000002 +120.05111111111111,-87.67777777777776,91.05,120.05111111111111,86.32888888888888,242.8 +120.10055555555556,-87.71388888888887,91.08749999999999,120.10055555555556,86.36444444444444,242.9 +120.14999999999999,-87.74999999999999,91.125,120.14999999999999,86.4,243.0 +120.19944444444444,-87.7861111111111,91.1625,120.19944444444444,86.43555555555555,243.10000000000002 +120.24888888888889,-87.82222222222221,91.2,120.24888888888889,86.47111111111111,243.20000000000002 +120.29833333333333,-87.85833333333332,91.2375,120.29833333333333,86.50666666666666,243.3 +120.34777777777778,-87.89444444444443,91.27499999999999,120.34777777777778,86.54222222222222,243.4 +120.39722222222223,-87.93055555555554,91.3125,120.39722222222223,86.57777777777778,243.5 +120.44666666666666,-87.96666666666665,91.35,120.44666666666666,86.61333333333333,243.60000000000002 +120.4961111111111,-88.00277777777777,91.3875,120.4961111111111,86.64888888888889,243.70000000000002 +120.54555555555555,-88.03888888888888,91.425,120.54555555555555,86.68444444444444,243.8 +120.595,-88.07499999999999,91.46249999999999,120.595,86.72,243.9 +120.64444444444445,-88.1111111111111,91.5,120.64444444444445,86.75555555555556,244.0 +120.69388888888889,-88.14722222222221,91.5375,120.69388888888889,86.7911111111111,244.10000000000002 +120.74333333333333,-88.18333333333332,91.575,120.74333333333333,86.82666666666667,244.20000000000002 +120.79277777777777,-88.21944444444443,91.6125,120.79277777777777,86.86222222222223,244.3 +120.84222222222222,-88.25555555555555,91.64999999999999,120.84222222222222,86.89777777777778,244.4 +120.89166666666667,-88.29166666666666,91.6875,120.89166666666667,86.93333333333334,244.5 +120.94111111111111,-88.32777777777777,91.725,120.94111111111111,86.96888888888888,244.60000000000002 +120.99055555555556,-88.36388888888888,91.7625,120.99055555555556,87.00444444444445,244.70000000000002 +121.03999999999999,-88.39999999999999,91.8,121.03999999999999,87.04,244.8 +121.08944444444444,-88.4361111111111,91.83749999999999,121.08944444444444,87.07555555555555,244.9 +121.13888888888889,-88.47222222222221,91.875,121.13888888888889,87.11111111111111,245.0 +121.18833333333333,-88.50833333333333,91.9125,121.18833333333333,87.14666666666666,245.10000000000002 +121.23777777777778,-88.54444444444444,91.95,121.23777777777778,87.18222222222222,245.20000000000002 +121.28722222222223,-88.58055555555555,91.9875,121.28722222222223,87.21777777777778,245.3 +121.33666666666666,-88.61666666666666,92.02499999999999,121.33666666666666,87.25333333333333,245.4 +121.3861111111111,-88.65277777777777,92.0625,121.3861111111111,87.28888888888889,245.5 +121.43555555555555,-88.68888888888888,92.1,121.43555555555555,87.32444444444444,245.60000000000002 +121.485,-88.725,92.1375,121.485,87.36,245.70000000000002 +121.53444444444445,-88.7611111111111,92.175,121.53444444444445,87.39555555555556,245.8 +121.5838888888889,-88.79722222222222,92.21249999999999,121.5838888888889,87.43111111111111,245.9 +121.63333333333333,-88.83333333333333,92.25,121.63333333333333,87.46666666666667,246.0 +121.68277777777777,-88.86944444444444,92.2875,121.68277777777777,87.50222222222222,246.10000000000002 +121.73222222222222,-88.90555555555555,92.325,121.73222222222222,87.53777777777778,246.20000000000002 +121.78166666666667,-88.94166666666666,92.3625,121.78166666666667,87.57333333333334,246.3 +121.83111111111111,-88.97777777777777,92.39999999999999,121.83111111111111,87.60888888888888,246.4 +121.88055555555556,-89.01388888888889,92.4375,121.88055555555556,87.64444444444445,246.5 +121.92999999999999,-89.05,92.475,121.92999999999999,87.68,246.60000000000002 +121.97944444444444,-89.08611111111111,92.5125,121.97944444444444,87.71555555555555,246.70000000000002 +122.02888888888889,-89.12222222222222,92.55,122.02888888888889,87.75111111111111,246.8 +122.07833333333333,-89.15833333333333,92.58749999999999,122.07833333333333,87.78666666666666,246.9 +122.12777777777778,-89.19444444444444,92.625,122.12777777777778,87.82222222222222,247.0 +122.17722222222223,-89.23055555555554,92.6625,122.17722222222223,87.85777777777778,247.10000000000002 +122.22666666666666,-89.26666666666665,92.7,122.22666666666666,87.89333333333333,247.20000000000002 +122.2761111111111,-89.30277777777776,92.7375,122.2761111111111,87.92888888888889,247.3 +122.32555555555555,-89.33888888888887,92.77499999999999,122.32555555555555,87.96444444444444,247.4 +122.375,-89.37499999999999,92.8125,122.375,88.0,247.5 +122.42444444444445,-89.4111111111111,92.85,122.42444444444445,88.03555555555556,247.60000000000002 +122.4738888888889,-89.44722222222221,92.8875,122.4738888888889,88.07111111111111,247.70000000000002 +122.52333333333333,-89.48333333333332,92.925,122.52333333333333,88.10666666666667,247.8 +122.57277777777777,-89.51944444444443,92.96249999999999,122.57277777777777,88.14222222222222,247.9 +122.62222222222222,-89.55555555555554,93.0,122.62222222222222,88.17777777777778,248.0 +122.67166666666667,-89.59166666666665,93.0375,122.67166666666667,88.21333333333334,248.10000000000002 +122.72111111111111,-89.62777777777777,93.075,122.72111111111111,88.24888888888889,248.20000000000002 +122.77055555555556,-89.66388888888888,93.1125,122.77055555555556,88.28444444444445,248.3 +122.82,-89.69999999999999,93.14999999999999,122.82,88.32,248.4 +122.86944444444444,-89.7361111111111,93.1875,122.86944444444444,88.35555555555555,248.5 +122.91888888888889,-89.77222222222221,93.225,122.91888888888889,88.39111111111112,248.60000000000002 +122.96833333333333,-89.80833333333332,93.2625,122.96833333333333,88.42666666666666,248.70000000000002 +123.01777777777778,-89.84444444444443,93.3,123.01777777777778,88.46222222222222,248.8 +123.06722222222221,-89.88055555555555,93.33749999999999,123.06722222222221,88.49777777777778,248.9 +123.11666666666666,-89.91666666666666,93.375,123.11666666666666,88.53333333333333,249.0 +123.1661111111111,-89.95277777777777,93.4125,123.1661111111111,88.56888888888889,249.10000000000002 +123.21555555555555,-89.98888888888888,93.45,123.21555555555555,88.60444444444444,249.20000000000002 +123.265,-90.02499999999999,93.4875,123.265,88.64,249.3 +123.31444444444445,-90.0611111111111,93.52499999999999,123.31444444444445,88.67555555555556,249.4 +123.36388888888888,-90.09722222222221,93.5625,123.36388888888888,88.71111111111111,249.5 +123.41333333333333,-90.13333333333333,93.6,123.41333333333333,88.74666666666667,249.60000000000002 +123.46277777777777,-90.16944444444444,93.6375,123.46277777777777,88.78222222222222,249.70000000000002 +123.51222222222222,-90.20555555555555,93.675,123.51222222222222,88.81777777777778,249.8 +123.56166666666667,-90.24166666666666,93.71249999999999,123.56166666666667,88.85333333333334,249.9 +123.61111111111111,-90.27777777777777,93.75,123.61111111111111,88.88888888888889,250.0 +123.66055555555555,-90.31388888888888,93.7875,123.66055555555555,88.92444444444445,250.10000000000002 +123.71,-90.35,93.825,123.71,88.96,250.20000000000002 +123.75944444444444,-90.3861111111111,93.8625,123.75944444444444,88.99555555555555,250.3 +123.80888888888889,-90.42222222222222,93.89999999999999,123.80888888888889,89.03111111111112,250.4 +123.85833333333333,-90.45833333333333,93.9375,123.85833333333333,89.06666666666666,250.5 +123.90777777777778,-90.49444444444444,93.975,123.90777777777778,89.10222222222222,250.60000000000002 +123.95722222222221,-90.53055555555555,94.0125,123.95722222222221,89.13777777777777,250.70000000000002 +124.00666666666666,-90.56666666666666,94.05,124.00666666666666,89.17333333333333,250.8 +124.05611111111111,-90.60277777777777,94.08749999999999,124.05611111111111,89.2088888888889,250.9 +124.10555555555555,-90.63888888888889,94.125,124.10555555555555,89.24444444444444,251.0 +124.155,-90.675,94.1625,124.155,89.28,251.10000000000002 +124.20444444444445,-90.71111111111111,94.2,124.20444444444445,89.31555555555556,251.20000000000002 +124.25388888888888,-90.74722222222222,94.2375,124.25388888888888,89.35111111111111,251.3 +124.30333333333333,-90.78333333333333,94.27499999999999,124.30333333333333,89.38666666666667,251.4 +124.35277777777777,-90.81944444444444,94.3125,124.35277777777777,89.42222222222222,251.5 +124.40222222222222,-90.85555555555554,94.35,124.40222222222222,89.45777777777778,251.60000000000002 +124.45166666666667,-90.89166666666665,94.3875,124.45166666666667,89.49333333333334,251.70000000000002 +124.50111111111111,-90.92777777777776,94.425,124.50111111111111,89.52888888888889,251.8 +124.55055555555555,-90.96388888888887,94.46249999999999,124.55055555555555,89.56444444444445,251.9 +124.6,-90.99999999999999,94.5,124.6,89.6,252.0 +124.64944444444444,-91.0361111111111,94.5375,124.64944444444444,89.63555555555556,252.10000000000002 +124.69888888888889,-91.07222222222221,94.575,124.69888888888889,89.67111111111112,252.20000000000002 +124.74833333333333,-91.10833333333332,94.6125,124.74833333333333,89.70666666666666,252.3 +124.79777777777778,-91.14444444444443,94.64999999999999,124.79777777777778,89.74222222222222,252.4 +124.84722222222221,-91.18055555555554,94.6875,124.84722222222221,89.77777777777777,252.5 +124.89666666666666,-91.21666666666665,94.725,124.89666666666666,89.81333333333333,252.60000000000002 +124.94611111111111,-91.25277777777777,94.7625,124.94611111111111,89.8488888888889,252.70000000000002 +124.99555555555555,-91.28888888888888,94.8,124.99555555555555,89.88444444444444,252.8 +125.045,-91.32499999999999,94.83749999999999,125.045,89.92,252.9 +125.09444444444445,-91.3611111111111,94.875,125.09444444444445,89.95555555555555,253.0 +125.14388888888888,-91.39722222222221,94.9125,125.14388888888888,89.99111111111111,253.10000000000002 +125.19333333333333,-91.43333333333332,94.95,125.19333333333333,90.02666666666667,253.20000000000002 +125.24277777777777,-91.46944444444443,94.9875,125.24277777777777,90.06222222222222,253.3 +125.29222222222222,-91.50555555555555,95.02499999999999,125.29222222222222,90.09777777777778,253.4 +125.34166666666667,-91.54166666666666,95.0625,125.34166666666667,90.13333333333334,253.5 +125.39111111111112,-91.57777777777777,95.1,125.39111111111112,90.16888888888889,253.60000000000002 +125.44055555555555,-91.61388888888888,95.1375,125.44055555555555,90.20444444444445,253.70000000000002 +125.49,-91.64999999999999,95.175,125.49,90.24,253.8 +125.53944444444444,-91.6861111111111,95.21249999999999,125.53944444444444,90.27555555555556,253.9 +125.58888888888889,-91.72222222222221,95.25,125.58888888888889,90.31111111111112,254.0 +125.63833333333334,-91.75833333333333,95.2875,125.63833333333334,90.34666666666666,254.10000000000002 +125.68777777777778,-91.79444444444444,95.325,125.68777777777778,90.38222222222223,254.20000000000002 +125.73722222222221,-91.83055555555555,95.3625,125.73722222222221,90.41777777777777,254.3 +125.78666666666666,-91.86666666666666,95.39999999999999,125.78666666666666,90.45333333333333,254.4 +125.83611111111111,-91.90277777777777,95.4375,125.83611111111111,90.4888888888889,254.5 +125.88555555555556,-91.93888888888888,95.475,125.88555555555556,90.52444444444444,254.60000000000002 +125.935,-91.975,95.5125,125.935,90.56,254.70000000000002 +125.98444444444445,-92.0111111111111,95.55,125.98444444444445,90.59555555555555,254.8 +126.03388888888888,-92.04722222222222,95.58749999999999,126.03388888888888,90.63111111111111,254.9 +126.08333333333333,-92.08333333333333,95.625,126.08333333333333,90.66666666666667,255.0 +126.13277777777778,-92.11944444444444,95.6625,126.13277777777778,90.70222222222222,255.10000000000002 +126.18222222222222,-92.15555555555555,95.7,126.18222222222222,90.73777777777778,255.20000000000002 +126.23166666666667,-92.19166666666666,95.7375,126.23166666666667,90.77333333333333,255.3 +126.28111111111112,-92.22777777777777,95.77499999999999,126.28111111111112,90.80888888888889,255.4 +126.33055555555555,-92.26388888888889,95.8125,126.33055555555555,90.84444444444445,255.5 +126.38,-92.3,95.85,126.38,90.88,255.60000000000002 +126.42944444444444,-92.33611111111111,95.8875,126.42944444444444,90.91555555555556,255.70000000000002 +126.47888888888889,-92.37222222222222,95.925,126.47888888888889,90.95111111111112,255.8 +126.52833333333334,-92.40833333333333,95.96249999999999,126.52833333333334,90.98666666666666,255.9 +126.57777777777778,-92.44444444444443,96.0,126.57777777777778,91.02222222222223,256.0 +126.62722222222222,-92.48055555555554,96.0375,126.62722222222222,91.05777777777777,256.1 +126.67666666666666,-92.51666666666665,96.075,126.67666666666666,91.09333333333333,256.2 +126.72611111111111,-92.55277777777776,96.1125,126.72611111111111,91.1288888888889,256.3 +126.77555555555556,-92.58888888888887,96.14999999999999,126.77555555555556,91.16444444444444,256.40000000000003 +126.825,-92.62499999999999,96.1875,126.825,91.2,256.5 +126.87444444444444,-92.6611111111111,96.225,126.87444444444444,91.23555555555555,256.6 +126.92388888888888,-92.69722222222221,96.2625,126.92388888888888,91.27111111111111,256.7 +126.97333333333333,-92.73333333333332,96.3,126.97333333333333,91.30666666666667,256.8 +127.02277777777778,-92.76944444444443,96.33749999999999,127.02277777777778,91.34222222222222,256.90000000000003 +127.07222222222222,-92.80555555555554,96.375,127.07222222222222,91.37777777777778,257.0 +127.12166666666667,-92.84166666666665,96.4125,127.12166666666667,91.41333333333333,257.1 +127.1711111111111,-92.87777777777777,96.45,127.1711111111111,91.44888888888889,257.2 +127.22055555555555,-92.91388888888888,96.4875,127.22055555555555,91.48444444444445,257.3 +127.27,-92.94999999999999,96.52499999999999,127.27,91.52,257.40000000000003 +127.31944444444444,-92.9861111111111,96.5625,127.31944444444444,91.55555555555556,257.5 +127.36888888888889,-93.02222222222221,96.6,127.36888888888889,91.5911111111111,257.6 +127.41833333333334,-93.05833333333332,96.6375,127.41833333333334,91.62666666666667,257.7 +127.46777777777777,-93.09444444444443,96.675,127.46777777777777,91.66222222222223,257.8 +127.51722222222222,-93.13055555555555,96.71249999999999,127.51722222222222,91.69777777777777,257.90000000000003 +127.56666666666666,-93.16666666666666,96.75,127.56666666666666,91.73333333333333,258.0 +127.61611111111111,-93.20277777777777,96.7875,127.61611111111111,91.7688888888889,258.1 +127.66555555555556,-93.23888888888888,96.825,127.66555555555556,91.80444444444444,258.2 +127.715,-93.27499999999999,96.8625,127.715,91.84,258.3 +127.76444444444444,-93.3111111111111,96.89999999999999,127.76444444444444,91.87555555555555,258.40000000000003 +127.81388888888888,-93.34722222222221,96.9375,127.81388888888888,91.91111111111111,258.5 +127.86333333333333,-93.38333333333333,96.975,127.86333333333333,91.94666666666667,258.6 +127.91277777777778,-93.41944444444444,97.0125,127.91277777777778,91.98222222222222,258.7 +127.96222222222222,-93.45555555555555,97.05,127.96222222222222,92.01777777777778,258.8 +128.01166666666666,-93.49166666666666,97.08749999999999,128.01166666666666,92.05333333333333,258.90000000000003 +128.0611111111111,-93.52777777777777,97.125,128.0611111111111,92.08888888888889,259.0 +128.11055555555555,-93.56388888888888,97.1625,128.11055555555555,92.12444444444445,259.1 +128.16,-93.6,97.2,128.16,92.16,259.2 +128.20944444444444,-93.6361111111111,97.2375,128.20944444444444,92.19555555555556,259.3 +128.2588888888889,-93.67222222222222,97.27499999999999,128.2588888888889,92.2311111111111,259.40000000000003 +128.30833333333334,-93.70833333333333,97.3125,128.30833333333334,92.26666666666667,259.5 +128.35777777777778,-93.74444444444444,97.35,128.35777777777778,92.30222222222223,259.6 +128.40722222222223,-93.78055555555555,97.3875,128.40722222222223,92.33777777777777,259.7 +128.45666666666668,-93.81666666666666,97.425,128.45666666666668,92.37333333333333,259.8 +128.5061111111111,-93.85277777777777,97.46249999999999,128.5061111111111,92.40888888888888,259.90000000000003 +128.55555555555554,-93.88888888888889,97.5,128.55555555555554,92.44444444444444,260.0 +128.605,-93.925,97.5375,128.605,92.48,260.1 +128.65444444444444,-93.96111111111111,97.575,128.65444444444444,92.51555555555555,260.2 +128.70388888888888,-93.99722222222222,97.6125,128.70388888888888,92.55111111111111,260.3 +128.75333333333333,-94.03333333333333,97.64999999999999,128.75333333333333,92.58666666666667,260.40000000000003 +128.80277777777778,-94.06944444444443,97.6875,128.80277777777778,92.62222222222222,260.5 +128.85222222222222,-94.10555555555554,97.725,128.85222222222222,92.65777777777778,260.6 +128.90166666666667,-94.14166666666665,97.7625,128.90166666666667,92.69333333333333,260.7 +128.95111111111112,-94.17777777777776,97.8,128.95111111111112,92.72888888888889,260.8 +129.00055555555556,-94.21388888888887,97.83749999999999,129.00055555555556,92.76444444444445,260.90000000000003 +129.05,-94.24999999999999,97.875,129.05,92.8,261.0 +129.09944444444443,-94.2861111111111,97.9125,129.09944444444443,92.83555555555556,261.1 +129.14888888888888,-94.32222222222221,97.95,129.14888888888888,92.8711111111111,261.2 +129.19833333333332,-94.35833333333332,97.9875,129.19833333333332,92.90666666666667,261.3 +129.24777777777777,-94.39444444444443,98.02499999999999,129.24777777777777,92.94222222222223,261.40000000000003 +129.29722222222222,-94.43055555555554,98.0625,129.29722222222222,92.97777777777777,261.5 +129.34666666666666,-94.46666666666665,98.1,129.34666666666666,93.01333333333334,261.6 +129.3961111111111,-94.50277777777777,98.1375,129.3961111111111,93.04888888888888,261.7 +129.44555555555556,-94.53888888888888,98.175,129.44555555555556,93.08444444444444,261.8 +129.495,-94.57499999999999,98.21249999999999,129.495,93.12,261.90000000000003 +129.54444444444445,-94.6111111111111,98.25,129.54444444444445,93.15555555555555,262.0 +129.5938888888889,-94.64722222222221,98.2875,129.5938888888889,93.19111111111111,262.1 +129.64333333333335,-94.68333333333332,98.325,129.64333333333335,93.22666666666667,262.2 +129.69277777777776,-94.71944444444443,98.3625,129.69277777777776,93.26222222222222,262.3 +129.7422222222222,-94.75555555555555,98.39999999999999,129.7422222222222,93.29777777777778,262.40000000000003 +129.79166666666666,-94.79166666666666,98.4375,129.79166666666666,93.33333333333333,262.5 +129.8411111111111,-94.82777777777777,98.475,129.8411111111111,93.36888888888889,262.6 +129.89055555555555,-94.86388888888888,98.5125,129.89055555555555,93.40444444444445,262.7 +129.94,-94.89999999999999,98.55,129.94,93.44,262.8 +129.98944444444444,-94.9361111111111,98.58749999999999,129.98944444444444,93.47555555555556,262.90000000000003 +130.0388888888889,-94.97222222222221,98.625,130.0388888888889,93.5111111111111,263.0 +130.08833333333334,-95.00833333333333,98.6625,130.08833333333334,93.54666666666667,263.1 +130.13777777777779,-95.04444444444444,98.7,130.13777777777779,93.58222222222223,263.2 +130.18722222222223,-95.08055555555555,98.7375,130.18722222222223,93.61777777777777,263.3 +130.23666666666665,-95.11666666666666,98.77499999999999,130.23666666666665,93.65333333333334,263.40000000000003 +130.2861111111111,-95.15277777777777,98.8125,130.2861111111111,93.68888888888888,263.5 +130.33555555555554,-95.18888888888888,98.85,130.33555555555554,93.72444444444444,263.6 +130.385,-95.225,98.8875,130.385,93.76,263.7 +130.43444444444444,-95.2611111111111,98.925,130.43444444444444,93.79555555555555,263.8 +130.48388888888888,-95.29722222222222,98.96249999999999,130.48388888888888,93.83111111111111,263.90000000000003 +130.53333333333333,-95.33333333333333,99.0,130.53333333333333,93.86666666666666,264.0 +130.58277777777778,-95.36944444444444,99.0375,130.58277777777778,93.90222222222222,264.1 +130.63222222222223,-95.40555555555555,99.075,130.63222222222223,93.93777777777778,264.2 +130.68166666666667,-95.44166666666666,99.1125,130.68166666666667,93.97333333333333,264.3 +130.73111111111112,-95.47777777777777,99.14999999999999,130.73111111111112,94.00888888888889,264.40000000000003 +130.78055555555557,-95.51388888888889,99.1875,130.78055555555557,94.04444444444445,264.5 +130.82999999999998,-95.55,99.225,130.82999999999998,94.08,264.6 +130.87944444444443,-95.58611111111111,99.2625,130.87944444444443,94.11555555555556,264.7 +130.92888888888888,-95.62222222222222,99.3,130.92888888888888,94.1511111111111,264.8 +130.97833333333332,-95.65833333333333,99.33749999999999,130.97833333333332,94.18666666666667,264.90000000000003 +131.02777777777777,-95.69444444444443,99.375,131.02777777777777,94.22222222222223,265.0 +131.07722222222222,-95.73055555555554,99.4125,131.07722222222222,94.25777777777778,265.1 +131.12666666666667,-95.76666666666665,99.45,131.12666666666667,94.29333333333334,265.2 +131.1761111111111,-95.80277777777776,99.4875,131.1761111111111,94.32888888888888,265.3 +131.22555555555556,-95.83888888888887,99.52499999999999,131.22555555555556,94.36444444444444,265.40000000000003 +131.275,-95.87499999999999,99.5625,131.275,94.4,265.5 +131.32444444444445,-95.9111111111111,99.6,131.32444444444445,94.43555555555555,265.6 +131.3738888888889,-95.94722222222221,99.6375,131.3738888888889,94.47111111111111,265.7 +131.42333333333332,-95.98333333333332,99.675,131.42333333333332,94.50666666666666,265.8 +131.47277777777776,-96.01944444444443,99.71249999999999,131.47277777777776,94.54222222222222,265.90000000000003 +131.5222222222222,-96.05555555555554,99.75,131.5222222222222,94.57777777777778,266.0 +131.57166666666666,-96.09166666666665,99.7875,131.57166666666666,94.61333333333333,266.1 +131.6211111111111,-96.12777777777777,99.825,131.6211111111111,94.64888888888889,266.2 +131.67055555555555,-96.16388888888888,99.8625,131.67055555555555,94.68444444444444,266.3 +131.72,-96.19999999999999,99.89999999999999,131.72,94.72,266.40000000000003 +131.76944444444445,-96.2361111111111,99.9375,131.76944444444445,94.75555555555556,266.5 +131.8188888888889,-96.27222222222221,99.975,131.8188888888889,94.7911111111111,266.6 +131.86833333333334,-96.30833333333332,100.0125,131.86833333333334,94.82666666666667,266.7 +131.9177777777778,-96.34444444444443,100.05,131.9177777777778,94.86222222222223,266.8 +131.96722222222223,-96.38055555555555,100.08749999999999,131.96722222222223,94.89777777777778,266.90000000000003 +132.01666666666665,-96.41666666666666,100.125,132.01666666666665,94.93333333333334,267.0 +132.0661111111111,-96.45277777777777,100.1625,132.0661111111111,94.96888888888888,267.1 +132.11555555555555,-96.48888888888888,100.2,132.11555555555555,95.00444444444445,267.2 +132.165,-96.52499999999999,100.2375,132.165,95.04,267.3 +132.21444444444444,-96.5611111111111,100.27499999999999,132.21444444444444,95.07555555555555,267.40000000000003 +132.26388888888889,-96.59722222222221,100.3125,132.26388888888889,95.11111111111111,267.5 +132.31333333333333,-96.63333333333333,100.35,132.31333333333333,95.14666666666666,267.6 +132.36277777777778,-96.66944444444444,100.3875,132.36277777777778,95.18222222222222,267.7 +132.41222222222223,-96.70555555555555,100.425,132.41222222222223,95.21777777777778,267.8 +132.46166666666667,-96.74166666666666,100.46249999999999,132.46166666666667,95.25333333333333,267.90000000000003 +132.51111111111112,-96.77777777777777,100.5,132.51111111111112,95.28888888888889,268.0 +132.56055555555557,-96.81388888888888,100.5375,132.56055555555557,95.32444444444444,268.1 +132.60999999999999,-96.85,100.575,132.60999999999999,95.36,268.2 +132.65944444444443,-96.8861111111111,100.6125,132.65944444444443,95.39555555555556,268.3 +132.70888888888888,-96.92222222222222,100.64999999999999,132.70888888888888,95.43111111111111,268.40000000000003 +132.75833333333333,-96.95833333333333,100.6875,132.75833333333333,95.46666666666667,268.5 +132.80777777777777,-96.99444444444444,100.725,132.80777777777777,95.50222222222222,268.6 +132.85722222222222,-97.03055555555555,100.7625,132.85722222222222,95.53777777777778,268.7 +132.90666666666667,-97.06666666666666,100.8,132.90666666666667,95.57333333333334,268.8 +132.9561111111111,-97.10277777777777,100.83749999999999,132.9561111111111,95.60888888888888,268.90000000000003 +133.00555555555556,-97.13888888888889,100.875,133.00555555555556,95.64444444444445,269.0 +133.055,-97.175,100.9125,133.055,95.68,269.1 +133.10444444444445,-97.21111111111111,100.95,133.10444444444445,95.71555555555555,269.2 +133.1538888888889,-97.24722222222222,100.9875,133.1538888888889,95.75111111111111,269.3 +133.20333333333332,-97.28333333333332,101.02499999999999,133.20333333333332,95.78666666666666,269.40000000000003 +133.25277777777777,-97.31944444444443,101.0625,133.25277777777777,95.82222222222222,269.5 +133.3022222222222,-97.35555555555554,101.1,133.3022222222222,95.85777777777778,269.6 +133.35166666666666,-97.39166666666665,101.1375,133.35166666666666,95.89333333333333,269.7 +133.4011111111111,-97.42777777777776,101.175,133.4011111111111,95.92888888888889,269.8 +133.45055555555555,-97.46388888888887,101.21249999999999,133.45055555555555,95.96444444444444,269.90000000000003 +133.5,-97.49999999999999,101.25,133.5,96.0,270.0 +133.54944444444445,-97.5361111111111,101.2875,133.54944444444445,96.03555555555556,270.1 +133.5988888888889,-97.57222222222221,101.325,133.5988888888889,96.07111111111111,270.2 +133.64833333333334,-97.60833333333332,101.3625,133.64833333333334,96.10666666666667,270.3 +133.6977777777778,-97.64444444444443,101.39999999999999,133.6977777777778,96.14222222222222,270.40000000000003 +133.74722222222223,-97.68055555555554,101.4375,133.74722222222223,96.17777777777778,270.5 +133.79666666666665,-97.71666666666665,101.475,133.79666666666665,96.21333333333334,270.6 +133.8461111111111,-97.75277777777777,101.5125,133.8461111111111,96.24888888888889,270.7 +133.89555555555555,-97.78888888888888,101.55,133.89555555555555,96.28444444444445,270.8 +133.945,-97.82499999999999,101.58749999999999,133.945,96.32,270.90000000000003 +133.99444444444444,-97.8611111111111,101.625,133.99444444444444,96.35555555555555,271.0 +134.0438888888889,-97.89722222222221,101.6625,134.0438888888889,96.39111111111112,271.1 +134.09333333333333,-97.93333333333332,101.7,134.09333333333333,96.42666666666666,271.2 +134.14277777777778,-97.96944444444443,101.7375,134.14277777777778,96.46222222222222,271.3 +134.19222222222223,-98.00555555555555,101.77499999999999,134.19222222222223,96.49777777777778,271.40000000000003 +134.24166666666667,-98.04166666666666,101.8125,134.24166666666667,96.53333333333333,271.5 +134.29111111111112,-98.07777777777777,101.85,134.29111111111112,96.56888888888889,271.6 +134.34055555555554,-98.11388888888888,101.8875,134.34055555555554,96.60444444444444,271.7 +134.39,-98.14999999999999,101.925,134.39,96.64,271.8 +134.43944444444443,-98.1861111111111,101.96249999999999,134.43944444444443,96.67555555555556,271.90000000000003 +134.48888888888888,-98.22222222222221,102.0,134.48888888888888,96.71111111111111,272.0 +134.53833333333333,-98.25833333333333,102.0375,134.53833333333333,96.74666666666667,272.1 +134.58777777777777,-98.29444444444444,102.075,134.58777777777777,96.78222222222222,272.2 +134.63722222222222,-98.33055555555555,102.1125,134.63722222222222,96.81777777777778,272.3 +134.68666666666667,-98.36666666666666,102.14999999999999,134.68666666666667,96.85333333333334,272.40000000000003 +134.73611111111111,-98.40277777777777,102.1875,134.73611111111111,96.88888888888889,272.5 +134.78555555555556,-98.43888888888888,102.225,134.78555555555556,96.92444444444445,272.6 +134.835,-98.475,102.2625,134.835,96.96,272.7 +134.88444444444445,-98.5111111111111,102.3,134.88444444444445,96.99555555555555,272.8 +134.93388888888887,-98.54722222222222,102.33749999999999,134.93388888888887,97.03111111111112,272.90000000000003 +134.98333333333332,-98.58333333333333,102.375,134.98333333333332,97.06666666666666,273.0 +135.03277777777777,-98.61944444444444,102.4125,135.03277777777777,97.10222222222222,273.1 +135.0822222222222,-98.65555555555555,102.45,135.0822222222222,97.13777777777777,273.2 +135.13166666666666,-98.69166666666666,102.4875,135.13166666666666,97.17333333333333,273.3 +135.1811111111111,-98.72777777777777,102.52499999999999,135.1811111111111,97.2088888888889,273.40000000000003 +135.23055555555555,-98.76388888888889,102.5625,135.23055555555555,97.24444444444444,273.5 +135.28,-98.8,102.6,135.28,97.28,273.6 +135.32944444444445,-98.83611111111111,102.6375,135.32944444444445,97.31555555555556,273.7 +135.3788888888889,-98.87222222222222,102.675,135.3788888888889,97.35111111111111,273.8 +135.42833333333334,-98.90833333333332,102.71249999999999,135.42833333333334,97.38666666666667,273.90000000000003 +135.4777777777778,-98.94444444444443,102.75,135.4777777777778,97.42222222222222,274.0 +135.5272222222222,-98.98055555555554,102.7875,135.5272222222222,97.45777777777778,274.1 +135.57666666666665,-99.01666666666665,102.825,135.57666666666665,97.49333333333334,274.2 +135.6261111111111,-99.05277777777776,102.8625,135.6261111111111,97.52888888888889,274.3 +135.67555555555555,-99.08888888888887,102.89999999999999,135.67555555555555,97.56444444444445,274.40000000000003 +135.725,-99.12499999999999,102.9375,135.725,97.6,274.5 +135.77444444444444,-99.1611111111111,102.975,135.77444444444444,97.63555555555556,274.6 +135.8238888888889,-99.19722222222221,103.0125,135.8238888888889,97.67111111111112,274.7 +135.87333333333333,-99.23333333333332,103.05,135.87333333333333,97.70666666666666,274.8 +135.92277777777778,-99.26944444444443,103.08749999999999,135.92277777777778,97.74222222222222,274.90000000000003 +135.97222222222223,-99.30555555555554,103.125,135.97222222222223,97.77777777777777,275.0 +136.02166666666668,-99.34166666666665,103.1625,136.02166666666668,97.81333333333333,275.1 +136.07111111111112,-99.37777777777777,103.2,136.07111111111112,97.8488888888889,275.2 +136.12055555555554,-99.41388888888888,103.2375,136.12055555555554,97.88444444444444,275.3 +136.17,-99.44999999999999,103.27499999999999,136.17,97.92,275.40000000000003 +136.21944444444443,-99.4861111111111,103.3125,136.21944444444443,97.95555555555555,275.5 +136.26888888888888,-99.52222222222221,103.35,136.26888888888888,97.99111111111111,275.6 +136.31833333333333,-99.55833333333332,103.3875,136.31833333333333,98.02666666666667,275.7 +136.36777777777777,-99.59444444444443,103.425,136.36777777777777,98.06222222222222,275.8 +136.41722222222222,-99.63055555555555,103.46249999999999,136.41722222222222,98.09777777777778,275.90000000000003 +136.46666666666667,-99.66666666666666,103.5,136.46666666666667,98.13333333333334,276.0 +136.51611111111112,-99.70277777777777,103.5375,136.51611111111112,98.16888888888889,276.1 +136.56555555555556,-99.73888888888888,103.575,136.56555555555556,98.20444444444445,276.2 +136.615,-99.77499999999999,103.6125,136.615,98.24,276.3 +136.66444444444446,-99.8111111111111,103.64999999999999,136.66444444444446,98.27555555555556,276.40000000000003 +136.71388888888887,-99.84722222222221,103.6875,136.71388888888887,98.31111111111112,276.5 +136.76333333333332,-99.88333333333333,103.725,136.76333333333332,98.34666666666666,276.6 +136.81277777777777,-99.91944444444444,103.7625,136.81277777777777,98.38222222222223,276.7 +136.86222222222221,-99.95555555555555,103.8,136.86222222222221,98.41777777777777,276.8 +136.91166666666666,-99.99166666666666,103.83749999999999,136.91166666666666,98.45333333333333,276.90000000000003 +136.9611111111111,-100.02777777777777,103.875,136.9611111111111,98.4888888888889,277.0 +137.01055555555556,-100.06388888888888,103.9125,137.01055555555556,98.52444444444444,277.1 +137.06,-100.1,103.95,137.06,98.56,277.2 +137.10944444444445,-100.1361111111111,103.9875,137.10944444444445,98.59555555555555,277.3 +137.1588888888889,-100.17222222222222,104.02499999999999,137.1588888888889,98.63111111111111,277.40000000000003 +137.20833333333334,-100.20833333333333,104.0625,137.20833333333334,98.66666666666667,277.5 +137.2577777777778,-100.24444444444444,104.1,137.2577777777778,98.70222222222222,277.6 +137.3072222222222,-100.28055555555555,104.1375,137.3072222222222,98.73777777777778,277.7 +137.35666666666665,-100.31666666666666,104.175,137.35666666666665,98.77333333333333,277.8 +137.4061111111111,-100.35277777777777,104.21249999999999,137.4061111111111,98.80888888888889,277.90000000000003 +137.45555555555555,-100.38888888888889,104.25,137.45555555555555,98.84444444444445,278.0 +137.505,-100.425,104.2875,137.505,98.88,278.1 +137.55444444444444,-100.46111111111111,104.325,137.55444444444444,98.91555555555556,278.2 +137.6038888888889,-100.4972222222222,104.3625,137.6038888888889,98.95111111111112,278.3 +137.65333333333334,-100.53333333333332,104.39999999999999,137.65333333333334,98.98666666666666,278.40000000000003 +137.70277777777778,-100.56944444444443,104.4375,137.70277777777778,99.02222222222223,278.5 +137.75222222222223,-100.60555555555554,104.475,137.75222222222223,99.05777777777777,278.6 +137.80166666666668,-100.64166666666665,104.5125,137.80166666666668,99.09333333333333,278.7 +137.8511111111111,-100.67777777777776,104.55,137.8511111111111,99.1288888888889,278.8 +137.90055555555554,-100.71388888888887,104.58749999999999,137.90055555555554,99.16444444444444,278.90000000000003 +137.95,-100.74999999999999,104.625,137.95,99.2,279.0 +137.99944444444444,-100.7861111111111,104.6625,137.99944444444444,99.23555555555555,279.1 +138.04888888888888,-100.82222222222221,104.7,138.04888888888888,99.27111111111111,279.2 +138.09833333333333,-100.85833333333332,104.7375,138.09833333333333,99.30666666666667,279.3 +138.14777777777778,-100.89444444444443,104.77499999999999,138.14777777777778,99.34222222222222,279.40000000000003 +138.19722222222222,-100.93055555555554,104.8125,138.19722222222222,99.37777777777778,279.5 +138.24666666666667,-100.96666666666665,104.85,138.24666666666667,99.41333333333333,279.6 +138.29611111111112,-101.00277777777777,104.8875,138.29611111111112,99.44888888888889,279.7 +138.34555555555556,-101.03888888888888,104.925,138.34555555555556,99.48444444444445,279.8 +138.395,-101.07499999999999,104.96249999999999,138.395,99.52,279.90000000000003 +138.44444444444443,-101.1111111111111,105.0,138.44444444444443,99.55555555555556,280.0 +138.49388888888888,-101.14722222222221,105.0375,138.49388888888888,99.5911111111111,280.1 +138.54333333333332,-101.18333333333332,105.075,138.54333333333332,99.62666666666667,280.2 +138.59277777777777,-101.21944444444443,105.1125,138.59277777777777,99.66222222222223,280.3 +138.64222222222222,-101.25555555555555,105.14999999999999,138.64222222222222,99.69777777777777,280.40000000000003 +138.69166666666666,-101.29166666666666,105.1875,138.69166666666666,99.73333333333333,280.5 +138.7411111111111,-101.32777777777777,105.225,138.7411111111111,99.7688888888889,280.6 +138.79055555555556,-101.36388888888888,105.2625,138.79055555555556,99.80444444444444,280.7 +138.84,-101.39999999999999,105.3,138.84,99.84,280.8 +138.88944444444445,-101.4361111111111,105.33749999999999,138.88944444444445,99.87555555555555,280.90000000000003 +138.9388888888889,-101.47222222222221,105.375,138.9388888888889,99.91111111111111,281.0 +138.98833333333334,-101.50833333333333,105.4125,138.98833333333334,99.94666666666667,281.1 +139.03777777777776,-101.54444444444444,105.45,139.03777777777776,99.98222222222222,281.2 +139.0872222222222,-101.58055555555555,105.4875,139.0872222222222,100.01777777777778,281.3 +139.13666666666666,-101.61666666666666,105.52499999999999,139.13666666666666,100.05333333333333,281.40000000000003 +139.1861111111111,-101.65277777777777,105.5625,139.1861111111111,100.08888888888889,281.5 +139.23555555555555,-101.68888888888888,105.6,139.23555555555555,100.12444444444445,281.6 +139.285,-101.725,105.6375,139.285,100.16,281.7 +139.33444444444444,-101.7611111111111,105.675,139.33444444444444,100.19555555555556,281.8 +139.3838888888889,-101.79722222222222,105.71249999999999,139.3838888888889,100.2311111111111,281.90000000000003 +139.43333333333334,-101.83333333333333,105.75,139.43333333333334,100.26666666666667,282.0 +139.48277777777778,-101.86944444444444,105.7875,139.48277777777778,100.30222222222223,282.1 +139.53222222222223,-101.90555555555555,105.825,139.53222222222223,100.33777777777777,282.2 +139.58166666666668,-101.94166666666666,105.8625,139.58166666666668,100.37333333333333,282.3 +139.6311111111111,-101.97777777777777,105.89999999999999,139.6311111111111,100.40888888888888,282.40000000000003 +139.68055555555554,-102.01388888888889,105.9375,139.68055555555554,100.44444444444444,282.5 +139.73,-102.05,105.975,139.73,100.48,282.6 +139.77944444444444,-102.08611111111111,106.0125,139.77944444444444,100.51555555555555,282.7 +139.82888888888888,-102.1222222222222,106.05,139.82888888888888,100.55111111111111,282.8 +139.87833333333333,-102.15833333333332,106.08749999999999,139.87833333333333,100.58666666666667,282.90000000000003 +139.92777777777778,-102.19444444444443,106.125,139.92777777777778,100.62222222222222,283.0 +139.97722222222222,-102.23055555555554,106.1625,139.97722222222222,100.65777777777778,283.1 +140.02666666666667,-102.26666666666665,106.2,140.02666666666667,100.69333333333333,283.2 +140.07611111111112,-102.30277777777776,106.2375,140.07611111111112,100.72888888888889,283.3 +140.12555555555556,-102.33888888888887,106.27499999999999,140.12555555555556,100.76444444444445,283.40000000000003 +140.175,-102.37499999999999,106.3125,140.175,100.8,283.5 +140.22444444444443,-102.4111111111111,106.35,140.22444444444443,100.83555555555556,283.6 +140.27388888888888,-102.44722222222221,106.3875,140.27388888888888,100.8711111111111,283.7 +140.32333333333332,-102.48333333333332,106.425,140.32333333333332,100.90666666666667,283.8 +140.37277777777777,-102.51944444444443,106.46249999999999,140.37277777777777,100.94222222222223,283.90000000000003 +140.42222222222222,-102.55555555555554,106.5,140.42222222222222,100.97777777777777,284.0 +140.47166666666666,-102.59166666666665,106.5375,140.47166666666666,101.01333333333334,284.1 +140.5211111111111,-102.62777777777777,106.575,140.5211111111111,101.04888888888888,284.2 +140.57055555555556,-102.66388888888888,106.6125,140.57055555555556,101.08444444444444,284.3 +140.62,-102.69999999999999,106.64999999999999,140.62,101.12,284.40000000000003 +140.66944444444445,-102.7361111111111,106.6875,140.66944444444445,101.15555555555555,284.5 +140.7188888888889,-102.77222222222221,106.725,140.7188888888889,101.19111111111111,284.6 +140.76833333333335,-102.80833333333332,106.7625,140.76833333333335,101.22666666666667,284.7 +140.81777777777776,-102.84444444444443,106.8,140.81777777777776,101.26222222222222,284.8 +140.8672222222222,-102.88055555555555,106.83749999999999,140.8672222222222,101.29777777777778,284.90000000000003 +140.91666666666666,-102.91666666666666,106.875,140.91666666666666,101.33333333333333,285.0 +140.9661111111111,-102.95277777777777,106.9125,140.9661111111111,101.36888888888889,285.1 +141.01555555555555,-102.98888888888888,106.95,141.01555555555555,101.40444444444445,285.2 +141.065,-103.02499999999999,106.9875,141.065,101.44,285.3 +141.11444444444444,-103.0611111111111,107.02499999999999,141.11444444444444,101.47555555555556,285.40000000000003 +141.1638888888889,-103.09722222222221,107.0625,141.1638888888889,101.5111111111111,285.5 +141.21333333333334,-103.13333333333333,107.1,141.21333333333334,101.54666666666667,285.6 +141.26277777777779,-103.16944444444444,107.1375,141.26277777777779,101.58222222222223,285.7 +141.31222222222223,-103.20555555555555,107.175,141.31222222222223,101.61777777777777,285.8 +141.36166666666665,-103.24166666666666,107.21249999999999,141.36166666666665,101.65333333333334,285.90000000000003 +141.4111111111111,-103.27777777777777,107.25,141.4111111111111,101.68888888888888,286.0 +141.46055555555554,-103.31388888888888,107.2875,141.46055555555554,101.72444444444444,286.1 +141.51,-103.35,107.325,141.51,101.76,286.2 +141.55944444444444,-103.3861111111111,107.3625,141.55944444444444,101.79555555555555,286.3 +141.60888888888888,-103.42222222222222,107.39999999999999,141.60888888888888,101.83111111111111,286.40000000000003 +141.65833333333333,-103.45833333333333,107.4375,141.65833333333333,101.86666666666666,286.5 +141.70777777777778,-103.49444444444444,107.475,141.70777777777778,101.90222222222222,286.6 +141.75722222222223,-103.53055555555555,107.5125,141.75722222222223,101.93777777777778,286.7 +141.80666666666667,-103.56666666666666,107.55,141.80666666666667,101.97333333333333,286.8 +141.85611111111112,-103.60277777777777,107.58749999999999,141.85611111111112,102.00888888888889,286.90000000000003 +141.90555555555557,-103.63888888888889,107.625,141.90555555555557,102.04444444444445,287.0 +141.95499999999998,-103.675,107.6625,141.95499999999998,102.08,287.1 +142.00444444444443,-103.7111111111111,107.7,142.00444444444443,102.11555555555556,287.2 +142.05388888888888,-103.7472222222222,107.7375,142.05388888888888,102.1511111111111,287.3 +142.10333333333332,-103.78333333333332,107.77499999999999,142.10333333333332,102.18666666666667,287.40000000000003 +142.15277777777777,-103.81944444444443,107.8125,142.15277777777777,102.22222222222223,287.5 +142.20222222222222,-103.85555555555554,107.85,142.20222222222222,102.25777777777778,287.6 +142.25166666666667,-103.89166666666665,107.8875,142.25166666666667,102.29333333333334,287.7 +142.3011111111111,-103.92777777777776,107.925,142.3011111111111,102.32888888888888,287.8 +142.35055555555556,-103.96388888888887,107.96249999999999,142.35055555555556,102.36444444444444,287.90000000000003 +142.4,-103.99999999999999,108.0,142.4,102.4,288.0 +142.44944444444445,-104.0361111111111,108.0375,142.44944444444445,102.43555555555555,288.1 +142.4988888888889,-104.07222222222221,108.075,142.4988888888889,102.47111111111111,288.2 +142.54833333333332,-104.10833333333332,108.1125,142.54833333333332,102.50666666666666,288.3 +142.59777777777776,-104.14444444444443,108.14999999999999,142.59777777777776,102.54222222222222,288.40000000000003 +142.6472222222222,-104.18055555555554,108.1875,142.6472222222222,102.57777777777778,288.5 +142.69666666666666,-104.21666666666665,108.225,142.69666666666666,102.61333333333333,288.6 +142.7461111111111,-104.25277777777777,108.2625,142.7461111111111,102.64888888888889,288.7 +142.79555555555555,-104.28888888888888,108.3,142.79555555555555,102.68444444444444,288.8 +142.845,-104.32499999999999,108.33749999999999,142.845,102.72,288.90000000000003 +142.89444444444445,-104.3611111111111,108.375,142.89444444444445,102.75555555555556,289.0 +142.9438888888889,-104.39722222222221,108.4125,142.9438888888889,102.7911111111111,289.1 +142.99333333333334,-104.43333333333332,108.45,142.99333333333334,102.82666666666667,289.2 +143.0427777777778,-104.46944444444443,108.4875,143.0427777777778,102.86222222222223,289.3 +143.09222222222223,-104.50555555555555,108.52499999999999,143.09222222222223,102.89777777777778,289.40000000000003 +143.14166666666665,-104.54166666666666,108.5625,143.14166666666665,102.93333333333334,289.5 +143.1911111111111,-104.57777777777777,108.6,143.1911111111111,102.96888888888888,289.6 +143.24055555555555,-104.61388888888888,108.6375,143.24055555555555,103.00444444444445,289.7 +143.29,-104.64999999999999,108.675,143.29,103.04,289.8 +143.33944444444444,-104.6861111111111,108.71249999999999,143.33944444444444,103.07555555555555,289.90000000000003 +143.38888888888889,-104.72222222222221,108.75,143.38888888888889,103.11111111111111,290.0 +143.43833333333333,-104.75833333333333,108.7875,143.43833333333333,103.14666666666666,290.1 +143.48777777777778,-104.79444444444444,108.825,143.48777777777778,103.18222222222222,290.2 +143.53722222222223,-104.83055555555555,108.8625,143.53722222222223,103.21777777777778,290.3 +143.58666666666667,-104.86666666666666,108.89999999999999,143.58666666666667,103.25333333333333,290.40000000000003 +143.63611111111112,-104.90277777777777,108.9375,143.63611111111112,103.28888888888889,290.5 +143.68555555555557,-104.93888888888888,108.975,143.68555555555557,103.32444444444444,290.6 +143.73499999999999,-104.975,109.0125,143.73499999999999,103.36,290.7 +143.78444444444443,-105.0111111111111,109.05,143.78444444444443,103.39555555555556,290.8 +143.83388888888888,-105.04722222222222,109.08749999999999,143.83388888888888,103.43111111111111,290.90000000000003 +143.88333333333333,-105.08333333333333,109.125,143.88333333333333,103.46666666666667,291.0 +143.93277777777777,-105.11944444444444,109.1625,143.93277777777777,103.50222222222222,291.1 +143.98222222222222,-105.15555555555555,109.2,143.98222222222222,103.53777777777778,291.2 +144.03166666666667,-105.19166666666666,109.2375,144.03166666666667,103.57333333333334,291.3 +144.0811111111111,-105.22777777777777,109.27499999999999,144.0811111111111,103.60888888888888,291.40000000000003 +144.13055555555556,-105.26388888888889,109.3125,144.13055555555556,103.64444444444445,291.5 +144.18,-105.3,109.35,144.18,103.68,291.6 +144.22944444444445,-105.3361111111111,109.3875,144.22944444444445,103.71555555555555,291.7 +144.2788888888889,-105.3722222222222,109.425,144.2788888888889,103.75111111111111,291.8 +144.32833333333332,-105.40833333333332,109.46249999999999,144.32833333333332,103.78666666666666,291.90000000000003 +144.37777777777777,-105.44444444444443,109.5,144.37777777777777,103.82222222222222,292.0 +144.4272222222222,-105.48055555555554,109.5375,144.4272222222222,103.85777777777778,292.1 +144.47666666666666,-105.51666666666665,109.575,144.47666666666666,103.89333333333333,292.2 +144.5261111111111,-105.55277777777776,109.6125,144.5261111111111,103.92888888888889,292.3 +144.57555555555555,-105.58888888888887,109.64999999999999,144.57555555555555,103.96444444444444,292.40000000000003 +144.625,-105.62499999999999,109.6875,144.625,104.0,292.5 +144.67444444444445,-105.6611111111111,109.725,144.67444444444445,104.03555555555556,292.6 +144.7238888888889,-105.69722222222221,109.7625,144.7238888888889,104.07111111111111,292.7 +144.77333333333334,-105.73333333333332,109.8,144.77333333333334,104.10666666666667,292.8 +144.8227777777778,-105.76944444444443,109.83749999999999,144.8227777777778,104.14222222222222,292.90000000000003 +144.8722222222222,-105.80555555555554,109.875,144.8722222222222,104.17777777777778,293.0 +144.92166666666665,-105.84166666666665,109.9125,144.92166666666665,104.21333333333334,293.1 +144.9711111111111,-105.87777777777777,109.95,144.9711111111111,104.24888888888889,293.2 +145.02055555555555,-105.91388888888888,109.9875,145.02055555555555,104.28444444444445,293.3 +145.07,-105.94999999999999,110.02499999999999,145.07,104.32,293.40000000000003 +145.11944444444444,-105.9861111111111,110.0625,145.11944444444444,104.35555555555555,293.5 +145.1688888888889,-106.02222222222221,110.1,145.1688888888889,104.39111111111112,293.6 +145.21833333333333,-106.05833333333332,110.1375,145.21833333333333,104.42666666666666,293.7 +145.26777777777778,-106.09444444444443,110.175,145.26777777777778,104.46222222222222,293.8 +145.31722222222223,-106.13055555555555,110.21249999999999,145.31722222222223,104.49777777777778,293.90000000000003 +145.36666666666667,-106.16666666666666,110.25,145.36666666666667,104.53333333333333,294.0 +145.41611111111112,-106.20277777777777,110.2875,145.41611111111112,104.56888888888889,294.1 +145.46555555555554,-106.23888888888888,110.325,145.46555555555554,104.60444444444444,294.2 +145.515,-106.27499999999999,110.3625,145.515,104.64,294.3 +145.56444444444443,-106.3111111111111,110.39999999999999,145.56444444444443,104.67555555555556,294.40000000000003 +145.61388888888888,-106.34722222222221,110.4375,145.61388888888888,104.71111111111111,294.5 +145.66333333333333,-106.38333333333333,110.475,145.66333333333333,104.74666666666667,294.6 +145.71277777777777,-106.41944444444444,110.5125,145.71277777777777,104.78222222222222,294.7 +145.76222222222222,-106.45555555555555,110.55,145.76222222222222,104.81777777777778,294.8 +145.81166666666667,-106.49166666666666,110.58749999999999,145.81166666666667,104.85333333333334,294.90000000000003 +145.86111111111111,-106.52777777777777,110.625,145.86111111111111,104.88888888888889,295.0 +145.91055555555556,-106.56388888888888,110.6625,145.91055555555556,104.92444444444445,295.1 +145.96,-106.6,110.7,145.96,104.96,295.2 +146.00944444444445,-106.6361111111111,110.7375,146.00944444444445,104.99555555555555,295.3 +146.05888888888887,-106.67222222222222,110.77499999999999,146.05888888888887,105.03111111111112,295.40000000000003 +146.10833333333332,-106.70833333333333,110.8125,146.10833333333332,105.06666666666666,295.5 +146.15777777777777,-106.74444444444444,110.85,146.15777777777777,105.10222222222222,295.6 +146.2072222222222,-106.78055555555555,110.8875,146.2072222222222,105.13777777777777,295.7 +146.25666666666666,-106.81666666666666,110.925,146.25666666666666,105.17333333333333,295.8 +146.3061111111111,-106.85277777777777,110.96249999999999,146.3061111111111,105.2088888888889,295.90000000000003 +146.35555555555555,-106.88888888888889,111.0,146.35555555555555,105.24444444444444,296.0 +146.405,-106.92499999999998,111.0375,146.405,105.28,296.1 +146.45444444444445,-106.9611111111111,111.075,146.45444444444445,105.31555555555556,296.2 +146.5038888888889,-106.9972222222222,111.1125,146.5038888888889,105.35111111111111,296.3 +146.55333333333334,-107.03333333333332,111.14999999999999,146.55333333333334,105.38666666666667,296.40000000000003 +146.6027777777778,-107.06944444444443,111.1875,146.6027777777778,105.42222222222222,296.5 +146.6522222222222,-107.10555555555554,111.225,146.6522222222222,105.45777777777778,296.6 +146.70166666666665,-107.14166666666665,111.2625,146.70166666666665,105.49333333333334,296.7 +146.7511111111111,-107.17777777777776,111.3,146.7511111111111,105.52888888888889,296.8 +146.80055555555555,-107.21388888888887,111.33749999999999,146.80055555555555,105.56444444444445,296.90000000000003 +146.85,-107.24999999999999,111.375,146.85,105.6,297.0 +146.89944444444444,-107.2861111111111,111.4125,146.89944444444444,105.63555555555556,297.1 +146.9488888888889,-107.32222222222221,111.45,146.9488888888889,105.67111111111112,297.2 +146.99833333333333,-107.35833333333332,111.4875,146.99833333333333,105.70666666666666,297.3 +147.04777777777778,-107.39444444444443,111.52499999999999,147.04777777777778,105.74222222222222,297.40000000000003 +147.09722222222223,-107.43055555555554,111.5625,147.09722222222223,105.77777777777777,297.5 +147.14666666666668,-107.46666666666665,111.6,147.14666666666668,105.81333333333333,297.6 +147.19611111111112,-107.50277777777777,111.6375,147.19611111111112,105.8488888888889,297.7 +147.24555555555554,-107.53888888888888,111.675,147.24555555555554,105.88444444444444,297.8 +147.295,-107.57499999999999,111.71249999999999,147.295,105.92,297.90000000000003 +147.34444444444443,-107.6111111111111,111.75,147.34444444444443,105.95555555555555,298.0 +147.39388888888888,-107.64722222222221,111.7875,147.39388888888888,105.99111111111111,298.1 +147.44333333333333,-107.68333333333332,111.825,147.44333333333333,106.02666666666667,298.2 +147.49277777777777,-107.71944444444443,111.8625,147.49277777777777,106.06222222222222,298.3 +147.54222222222222,-107.75555555555555,111.89999999999999,147.54222222222222,106.09777777777778,298.40000000000003 +147.59166666666667,-107.79166666666666,111.9375,147.59166666666667,106.13333333333334,298.5 +147.64111111111112,-107.82777777777777,111.975,147.64111111111112,106.16888888888889,298.6 +147.69055555555556,-107.86388888888888,112.0125,147.69055555555556,106.20444444444445,298.7 +147.74,-107.89999999999999,112.05,147.74,106.24,298.8 +147.78944444444446,-107.9361111111111,112.08749999999999,147.78944444444446,106.27555555555556,298.90000000000003 +147.83888888888887,-107.97222222222221,112.125,147.83888888888887,106.31111111111112,299.0 +147.88833333333332,-108.00833333333333,112.1625,147.88833333333332,106.34666666666666,299.1 +147.93777777777777,-108.04444444444444,112.2,147.93777777777777,106.38222222222223,299.2 +147.98722222222221,-108.08055555555555,112.2375,147.98722222222221,106.41777777777777,299.3 +148.03666666666666,-108.11666666666666,112.27499999999999,148.03666666666666,106.45333333333333,299.40000000000003 +148.0861111111111,-108.15277777777777,112.3125,148.0861111111111,106.4888888888889,299.5 +148.13555555555556,-108.18888888888888,112.35,148.13555555555556,106.52444444444444,299.6 +148.185,-108.225,112.3875,148.185,106.56,299.7 +148.23444444444445,-108.2611111111111,112.425,148.23444444444445,106.59555555555555,299.8 +148.2838888888889,-108.29722222222222,112.46249999999999,148.2838888888889,106.63111111111111,299.90000000000003 +148.33333333333334,-108.33333333333333,112.5,148.33333333333334,106.66666666666667,300.0 +148.38277777777776,-108.36944444444444,112.5375,148.38277777777776,106.70222222222222,300.1 +148.4322222222222,-108.40555555555555,112.575,148.4322222222222,106.73777777777778,300.2 +148.48166666666665,-108.44166666666666,112.6125,148.48166666666665,106.77333333333333,300.3 +148.5311111111111,-108.47777777777777,112.64999999999999,148.5311111111111,106.80888888888889,300.40000000000003 +148.58055555555555,-108.51388888888889,112.6875,148.58055555555555,106.84444444444445,300.5 +148.63,-108.54999999999998,112.725,148.63,106.88,300.6 +148.67944444444444,-108.5861111111111,112.7625,148.67944444444444,106.91555555555556,300.7 +148.7288888888889,-108.6222222222222,112.8,148.7288888888889,106.95111111111112,300.8 +148.77833333333334,-108.65833333333332,112.83749999999999,148.77833333333334,106.98666666666666,300.90000000000003 +148.82777777777778,-108.69444444444443,112.875,148.82777777777778,107.02222222222223,301.0 +148.87722222222223,-108.73055555555554,112.9125,148.87722222222223,107.05777777777777,301.1 +148.92666666666668,-108.76666666666665,112.95,148.92666666666668,107.09333333333333,301.2 +148.9761111111111,-108.80277777777776,112.9875,148.9761111111111,107.1288888888889,301.3 +149.02555555555554,-108.83888888888887,113.02499999999999,149.02555555555554,107.16444444444444,301.40000000000003 +149.075,-108.87499999999999,113.0625,149.075,107.2,301.5 +149.12444444444444,-108.9111111111111,113.1,149.12444444444444,107.23555555555555,301.6 +149.17388888888888,-108.94722222222221,113.1375,149.17388888888888,107.27111111111111,301.7 +149.22333333333333,-108.98333333333332,113.175,149.22333333333333,107.30666666666667,301.8 +149.27277777777778,-109.01944444444443,113.21249999999999,149.27277777777778,107.34222222222222,301.90000000000003 +149.32222222222222,-109.05555555555554,113.25,149.32222222222222,107.37777777777778,302.0 +149.37166666666667,-109.09166666666665,113.2875,149.37166666666667,107.41333333333333,302.1 +149.42111111111112,-109.12777777777777,113.325,149.42111111111112,107.44888888888889,302.2 +149.47055555555556,-109.16388888888888,113.3625,149.47055555555556,107.48444444444445,302.3 +149.52,-109.19999999999999,113.39999999999999,149.52,107.52,302.40000000000003 +149.56944444444443,-109.2361111111111,113.4375,149.56944444444443,107.55555555555556,302.5 +149.61888888888888,-109.27222222222221,113.475,149.61888888888888,107.5911111111111,302.6 +149.66833333333332,-109.30833333333332,113.5125,149.66833333333332,107.62666666666667,302.7 +149.71777777777777,-109.34444444444443,113.55,149.71777777777777,107.66222222222223,302.8 +149.76722222222222,-109.38055555555555,113.58749999999999,149.76722222222222,107.69777777777777,302.90000000000003 +149.81666666666666,-109.41666666666666,113.625,149.81666666666666,107.73333333333333,303.0 +149.8661111111111,-109.45277777777777,113.6625,149.8661111111111,107.7688888888889,303.1 +149.91555555555556,-109.48888888888888,113.7,149.91555555555556,107.80444444444444,303.2 +149.965,-109.52499999999999,113.7375,149.965,107.84,303.3 +150.01444444444445,-109.5611111111111,113.77499999999999,150.01444444444445,107.87555555555555,303.40000000000003 +150.0638888888889,-109.59722222222221,113.8125,150.0638888888889,107.91111111111111,303.5 +150.11333333333334,-109.63333333333333,113.85,150.11333333333334,107.94666666666667,303.6 +150.16277777777776,-109.66944444444444,113.8875,150.16277777777776,107.98222222222222,303.7 +150.2122222222222,-109.70555555555555,113.925,150.2122222222222,108.01777777777778,303.8 +150.26166666666666,-109.74166666666666,113.96249999999999,150.26166666666666,108.05333333333333,303.90000000000003 +150.3111111111111,-109.77777777777777,114.0,150.3111111111111,108.08888888888889,304.0 +150.36055555555555,-109.81388888888888,114.0375,150.36055555555555,108.12444444444445,304.1 +150.41,-109.85,114.075,150.41,108.16,304.2 +150.45944444444444,-109.8861111111111,114.1125,150.45944444444444,108.19555555555556,304.3 +150.5088888888889,-109.92222222222222,114.14999999999999,150.5088888888889,108.2311111111111,304.40000000000003 +150.55833333333334,-109.95833333333333,114.1875,150.55833333333334,108.26666666666667,304.5 +150.60777777777778,-109.99444444444444,114.225,150.60777777777778,108.30222222222223,304.6 +150.65722222222223,-110.03055555555555,114.2625,150.65722222222223,108.33777777777777,304.7 +150.70666666666668,-110.06666666666666,114.3,150.70666666666668,108.37333333333333,304.8 +150.7561111111111,-110.10277777777777,114.33749999999999,150.7561111111111,108.40888888888888,304.90000000000003 +150.80555555555554,-110.13888888888887,114.375,150.80555555555554,108.44444444444444,305.0 +150.855,-110.17499999999998,114.4125,150.855,108.48,305.1 +150.90444444444444,-110.2111111111111,114.45,150.90444444444444,108.51555555555555,305.2 +150.95388888888888,-110.2472222222222,114.4875,150.95388888888888,108.55111111111111,305.3 +151.00333333333333,-110.28333333333332,114.52499999999999,151.00333333333333,108.58666666666667,305.40000000000003 +151.05277777777778,-110.31944444444443,114.5625,151.05277777777778,108.62222222222222,305.5 +151.10222222222222,-110.35555555555554,114.6,151.10222222222222,108.65777777777778,305.6 +151.15166666666667,-110.39166666666665,114.6375,151.15166666666667,108.69333333333333,305.7 +151.20111111111112,-110.42777777777776,114.675,151.20111111111112,108.72888888888889,305.8 +151.25055555555556,-110.46388888888887,114.71249999999999,151.25055555555556,108.76444444444445,305.90000000000003 +151.3,-110.49999999999999,114.75,151.3,108.8,306.0 +151.34944444444443,-110.5361111111111,114.7875,151.34944444444443,108.83555555555556,306.1 +151.39888888888888,-110.57222222222221,114.825,151.39888888888888,108.8711111111111,306.2 +151.44833333333332,-110.60833333333332,114.8625,151.44833333333332,108.90666666666667,306.3 +151.49777777777777,-110.64444444444443,114.89999999999999,151.49777777777777,108.94222222222223,306.40000000000003 +151.54722222222222,-110.68055555555554,114.9375,151.54722222222222,108.97777777777777,306.5 +151.59666666666666,-110.71666666666665,114.975,151.59666666666666,109.01333333333334,306.6 +151.6461111111111,-110.75277777777777,115.0125,151.6461111111111,109.04888888888888,306.7 +151.69555555555556,-110.78888888888888,115.05,151.69555555555556,109.08444444444444,306.8 +151.745,-110.82499999999999,115.08749999999999,151.745,109.12,306.90000000000003 +151.79444444444445,-110.8611111111111,115.125,151.79444444444445,109.15555555555555,307.0 +151.8438888888889,-110.89722222222221,115.1625,151.8438888888889,109.19111111111111,307.1 +151.89333333333332,-110.93333333333332,115.19999999999999,151.89333333333332,109.22666666666666,307.20000000000005 +151.94277777777776,-110.96944444444443,115.2375,151.94277777777776,109.26222222222222,307.3 +151.9922222222222,-111.00555555555555,115.27499999999999,151.9922222222222,109.29777777777778,307.40000000000003 +152.04166666666666,-111.04166666666666,115.3125,152.04166666666666,109.33333333333333,307.5 +152.0911111111111,-111.07777777777777,115.35,152.0911111111111,109.36888888888889,307.6 +152.14055555555555,-111.11388888888888,115.38749999999999,152.14055555555555,109.40444444444445,307.70000000000005 +152.19,-111.14999999999999,115.425,152.19,109.44,307.8 +152.23944444444444,-111.1861111111111,115.46249999999999,152.23944444444444,109.47555555555556,307.90000000000003 +152.2888888888889,-111.22222222222221,115.5,152.2888888888889,109.5111111111111,308.0 +152.33833333333334,-111.25833333333333,115.5375,152.33833333333334,109.54666666666667,308.1 +152.38777777777779,-111.29444444444444,115.57499999999999,152.38777777777779,109.58222222222223,308.20000000000005 +152.43722222222223,-111.33055555555555,115.6125,152.43722222222223,109.61777777777777,308.3 +152.48666666666665,-111.36666666666666,115.64999999999999,152.48666666666665,109.65333333333334,308.40000000000003 +152.5361111111111,-111.40277777777777,115.6875,152.5361111111111,109.68888888888888,308.5 +152.58555555555554,-111.43888888888888,115.725,152.58555555555554,109.72444444444444,308.6 +152.635,-111.475,115.76249999999999,152.635,109.76,308.70000000000005 +152.68444444444444,-111.5111111111111,115.8,152.68444444444444,109.79555555555555,308.8 +152.73388888888888,-111.54722222222222,115.83749999999999,152.73388888888888,109.83111111111111,308.90000000000003 +152.78333333333333,-111.58333333333333,115.875,152.78333333333333,109.86666666666666,309.0 +152.83277777777778,-111.61944444444444,115.9125,152.83277777777778,109.90222222222222,309.1 +152.88222222222223,-111.65555555555555,115.94999999999999,152.88222222222223,109.93777777777778,309.20000000000005 +152.93166666666667,-111.69166666666666,115.9875,152.93166666666667,109.97333333333333,309.3 +152.98111111111112,-111.72777777777777,116.02499999999999,152.98111111111112,110.00888888888889,309.40000000000003 +153.03055555555557,-111.76388888888887,116.0625,153.03055555555557,110.04444444444445,309.5 +153.07999999999998,-111.79999999999998,116.1,153.07999999999998,110.08,309.6 +153.12944444444443,-111.8361111111111,116.13749999999999,153.12944444444443,110.11555555555556,309.70000000000005 +153.17888888888888,-111.8722222222222,116.175,153.17888888888888,110.1511111111111,309.8 +153.22833333333332,-111.90833333333332,116.21249999999999,153.22833333333332,110.18666666666667,309.90000000000003 +153.27777777777777,-111.94444444444443,116.25,153.27777777777777,110.22222222222223,310.0 +153.32722222222222,-111.98055555555554,116.2875,153.32722222222222,110.25777777777778,310.1 +153.37666666666667,-112.01666666666665,116.32499999999999,153.37666666666667,110.29333333333334,310.20000000000005 +153.4261111111111,-112.05277777777776,116.3625,153.4261111111111,110.32888888888888,310.3 +153.47555555555556,-112.08888888888887,116.39999999999999,153.47555555555556,110.36444444444444,310.40000000000003 +153.525,-112.12499999999999,116.4375,153.525,110.4,310.5 +153.57444444444445,-112.1611111111111,116.475,153.57444444444445,110.43555555555555,310.6 +153.6238888888889,-112.19722222222221,116.51249999999999,153.6238888888889,110.47111111111111,310.70000000000005 +153.67333333333332,-112.23333333333332,116.55,153.67333333333332,110.50666666666666,310.8 +153.72277777777776,-112.26944444444443,116.58749999999999,153.72277777777776,110.54222222222222,310.90000000000003 +153.7722222222222,-112.30555555555554,116.625,153.7722222222222,110.57777777777778,311.0 +153.82166666666666,-112.34166666666665,116.6625,153.82166666666666,110.61333333333333,311.1 +153.8711111111111,-112.37777777777777,116.69999999999999,153.8711111111111,110.64888888888889,311.20000000000005 +153.92055555555555,-112.41388888888888,116.7375,153.92055555555555,110.68444444444444,311.3 +153.97,-112.44999999999999,116.77499999999999,153.97,110.72,311.40000000000003 +154.01944444444445,-112.4861111111111,116.8125,154.01944444444445,110.75555555555556,311.5 +154.0688888888889,-112.52222222222221,116.85,154.0688888888889,110.7911111111111,311.6 +154.11833333333334,-112.55833333333332,116.88749999999999,154.11833333333334,110.82666666666667,311.70000000000005 +154.1677777777778,-112.59444444444443,116.925,154.1677777777778,110.86222222222223,311.8 +154.21722222222223,-112.63055555555555,116.96249999999999,154.21722222222223,110.89777777777778,311.90000000000003 +154.26666666666665,-112.66666666666666,117.0,154.26666666666665,110.93333333333334,312.0 +154.3161111111111,-112.70277777777777,117.0375,154.3161111111111,110.96888888888888,312.1 +154.36555555555555,-112.73888888888888,117.07499999999999,154.36555555555555,111.00444444444445,312.20000000000005 +154.415,-112.77499999999999,117.1125,154.415,111.04,312.3 +154.46444444444444,-112.8111111111111,117.14999999999999,154.46444444444444,111.07555555555555,312.40000000000003 +154.51388888888889,-112.84722222222221,117.1875,154.51388888888889,111.11111111111111,312.5 +154.56333333333333,-112.88333333333333,117.225,154.56333333333333,111.14666666666666,312.6 +154.61277777777778,-112.91944444444444,117.26249999999999,154.61277777777778,111.18222222222222,312.70000000000005 +154.66222222222223,-112.95555555555555,117.3,154.66222222222223,111.21777777777778,312.8 +154.71166666666667,-112.99166666666666,117.33749999999999,154.71166666666667,111.25333333333333,312.90000000000003 +154.76111111111112,-113.02777777777777,117.375,154.76111111111112,111.28888888888889,313.0 +154.81055555555557,-113.06388888888888,117.4125,154.81055555555557,111.32444444444444,313.1 +154.85999999999999,-113.1,117.44999999999999,154.85999999999999,111.36,313.20000000000005 +154.90944444444443,-113.1361111111111,117.4875,154.90944444444443,111.39555555555556,313.3 +154.95888888888888,-113.17222222222222,117.52499999999999,154.95888888888888,111.43111111111111,313.40000000000003 +155.00833333333333,-113.20833333333333,117.5625,155.00833333333333,111.46666666666667,313.5 +155.05777777777777,-113.24444444444444,117.6,155.05777777777777,111.50222222222222,313.6 +155.10722222222222,-113.28055555555555,117.63749999999999,155.10722222222222,111.53777777777778,313.70000000000005 +155.15666666666667,-113.31666666666666,117.675,155.15666666666667,111.57333333333334,313.8 +155.2061111111111,-113.35277777777776,117.71249999999999,155.2061111111111,111.60888888888888,313.90000000000003 +155.25555555555556,-113.38888888888887,117.75,155.25555555555556,111.64444444444445,314.0 +155.305,-113.42499999999998,117.7875,155.305,111.68,314.1 +155.35444444444445,-113.4611111111111,117.82499999999999,155.35444444444445,111.71555555555555,314.20000000000005 +155.4038888888889,-113.4972222222222,117.8625,155.4038888888889,111.75111111111111,314.3 +155.45333333333332,-113.53333333333332,117.89999999999999,155.45333333333332,111.78666666666666,314.40000000000003 +155.50277777777777,-113.56944444444443,117.9375,155.50277777777777,111.82222222222222,314.5 +155.5522222222222,-113.60555555555554,117.975,155.5522222222222,111.85777777777778,314.6 +155.60166666666666,-113.64166666666665,118.01249999999999,155.60166666666666,111.89333333333333,314.70000000000005 +155.6511111111111,-113.67777777777776,118.05,155.6511111111111,111.92888888888889,314.8 +155.70055555555555,-113.71388888888887,118.08749999999999,155.70055555555555,111.96444444444444,314.90000000000003 +155.75,-113.74999999999999,118.125,155.75,112.0,315.0 +155.79944444444445,-113.7861111111111,118.1625,155.79944444444445,112.03555555555556,315.1 +155.8488888888889,-113.82222222222221,118.19999999999999,155.8488888888889,112.07111111111111,315.20000000000005 +155.89833333333334,-113.85833333333332,118.2375,155.89833333333334,112.10666666666667,315.3 +155.9477777777778,-113.89444444444443,118.27499999999999,155.9477777777778,112.14222222222222,315.40000000000003 +155.9972222222222,-113.93055555555554,118.3125,155.9972222222222,112.17777777777778,315.5 +156.04666666666665,-113.96666666666665,118.35,156.04666666666665,112.21333333333334,315.6 +156.0961111111111,-114.00277777777777,118.38749999999999,156.0961111111111,112.24888888888889,315.70000000000005 +156.14555555555555,-114.03888888888888,118.425,156.14555555555555,112.28444444444445,315.8 +156.195,-114.07499999999999,118.46249999999999,156.195,112.32,315.90000000000003 +156.24444444444444,-114.1111111111111,118.5,156.24444444444444,112.35555555555555,316.0 +156.2938888888889,-114.14722222222221,118.5375,156.2938888888889,112.39111111111112,316.1 +156.34333333333333,-114.18333333333332,118.57499999999999,156.34333333333333,112.42666666666666,316.20000000000005 +156.39277777777778,-114.21944444444443,118.6125,156.39277777777778,112.46222222222222,316.3 +156.44222222222223,-114.25555555555555,118.64999999999999,156.44222222222223,112.49777777777778,316.40000000000003 +156.49166666666667,-114.29166666666666,118.6875,156.49166666666667,112.53333333333333,316.5 +156.54111111111112,-114.32777777777777,118.725,156.54111111111112,112.56888888888889,316.6 +156.59055555555554,-114.36388888888888,118.76249999999999,156.59055555555554,112.60444444444444,316.70000000000005 +156.64,-114.39999999999999,118.8,156.64,112.64,316.8 +156.68944444444443,-114.4361111111111,118.83749999999999,156.68944444444443,112.67555555555556,316.90000000000003 +156.73888888888888,-114.47222222222221,118.875,156.73888888888888,112.71111111111111,317.0 +156.78833333333333,-114.50833333333333,118.9125,156.78833333333333,112.74666666666667,317.1 +156.83777777777777,-114.54444444444444,118.94999999999999,156.83777777777777,112.78222222222222,317.20000000000005 +156.88722222222222,-114.58055555555555,118.9875,156.88722222222222,112.81777777777778,317.3 +156.93666666666667,-114.61666666666666,119.02499999999999,156.93666666666667,112.85333333333334,317.40000000000003 +156.98611111111111,-114.65277777777777,119.0625,156.98611111111111,112.88888888888889,317.5 +157.03555555555556,-114.68888888888888,119.1,157.03555555555556,112.92444444444445,317.6 +157.085,-114.725,119.13749999999999,157.085,112.96,317.70000000000005 +157.13444444444445,-114.7611111111111,119.175,157.13444444444445,112.99555555555555,317.8 +157.18388888888887,-114.79722222222222,119.21249999999999,157.18388888888887,113.03111111111112,317.90000000000003 +157.23333333333332,-114.83333333333333,119.25,157.23333333333332,113.06666666666666,318.0 +157.28277777777777,-114.86944444444444,119.2875,157.28277777777777,113.10222222222222,318.1 +157.3322222222222,-114.90555555555555,119.32499999999999,157.3322222222222,113.13777777777777,318.20000000000005 +157.38166666666666,-114.94166666666666,119.3625,157.38166666666666,113.17333333333333,318.3 +157.4311111111111,-114.97777777777776,119.39999999999999,157.4311111111111,113.2088888888889,318.40000000000003 +157.48055555555555,-115.01388888888887,119.4375,157.48055555555555,113.24444444444444,318.5 +157.53,-115.04999999999998,119.475,157.53,113.28,318.6 +157.57944444444445,-115.0861111111111,119.51249999999999,157.57944444444445,113.31555555555556,318.70000000000005 +157.6288888888889,-115.1222222222222,119.55,157.6288888888889,113.35111111111111,318.8 +157.67833333333334,-115.15833333333332,119.58749999999999,157.67833333333334,113.38666666666667,318.90000000000003 +157.7277777777778,-115.19444444444443,119.625,157.7277777777778,113.42222222222222,319.0 +157.7772222222222,-115.23055555555554,119.6625,157.7772222222222,113.45777777777778,319.1 +157.82666666666665,-115.26666666666665,119.69999999999999,157.82666666666665,113.49333333333334,319.20000000000005 +157.8761111111111,-115.30277777777776,119.7375,157.8761111111111,113.52888888888889,319.3 +157.92555555555555,-115.33888888888887,119.77499999999999,157.92555555555555,113.56444444444445,319.40000000000003 +157.975,-115.37499999999999,119.8125,157.975,113.6,319.5 +158.02444444444444,-115.4111111111111,119.85,158.02444444444444,113.63555555555556,319.6 +158.0738888888889,-115.44722222222221,119.88749999999999,158.0738888888889,113.67111111111112,319.70000000000005 +158.12333333333333,-115.48333333333332,119.925,158.12333333333333,113.70666666666666,319.8 +158.17277777777778,-115.51944444444443,119.96249999999999,158.17277777777778,113.74222222222222,319.90000000000003 +158.22222222222223,-115.55555555555554,120.0,158.22222222222223,113.77777777777777,320.0 +158.27166666666668,-115.59166666666665,120.0375,158.27166666666668,113.81333333333333,320.1 +158.32111111111112,-115.62777777777777,120.07499999999999,158.32111111111112,113.8488888888889,320.20000000000005 +158.37055555555554,-115.66388888888888,120.1125,158.37055555555554,113.88444444444444,320.3 +158.42,-115.69999999999999,120.14999999999999,158.42,113.92,320.40000000000003 +158.46944444444443,-115.7361111111111,120.1875,158.46944444444443,113.95555555555555,320.5 +158.51888888888888,-115.77222222222221,120.225,158.51888888888888,113.99111111111111,320.6 +158.56833333333333,-115.80833333333332,120.26249999999999,158.56833333333333,114.02666666666667,320.70000000000005 +158.61777777777777,-115.84444444444443,120.3,158.61777777777777,114.06222222222222,320.8 +158.66722222222222,-115.88055555555555,120.33749999999999,158.66722222222222,114.09777777777778,320.90000000000003 +158.71666666666667,-115.91666666666666,120.375,158.71666666666667,114.13333333333334,321.0 +158.76611111111112,-115.95277777777777,120.4125,158.76611111111112,114.16888888888889,321.1 +158.81555555555556,-115.98888888888888,120.44999999999999,158.81555555555556,114.20444444444445,321.20000000000005 +158.865,-116.02499999999999,120.4875,158.865,114.24,321.3 +158.91444444444446,-116.0611111111111,120.52499999999999,158.91444444444446,114.27555555555556,321.40000000000003 +158.96388888888887,-116.09722222222221,120.5625,158.96388888888887,114.31111111111112,321.5 +159.01333333333332,-116.13333333333333,120.6,159.01333333333332,114.34666666666666,321.6 +159.06277777777777,-116.16944444444444,120.63749999999999,159.06277777777777,114.38222222222223,321.70000000000005 +159.11222222222221,-116.20555555555555,120.675,159.11222222222221,114.41777777777777,321.8 +159.16166666666666,-116.24166666666666,120.71249999999999,159.16166666666666,114.45333333333333,321.90000000000003 +159.2111111111111,-116.27777777777777,120.75,159.2111111111111,114.4888888888889,322.0 +159.26055555555556,-116.31388888888888,120.7875,159.26055555555556,114.52444444444444,322.1 +159.31,-116.35,120.82499999999999,159.31,114.56,322.20000000000005 +159.35944444444445,-116.3861111111111,120.8625,159.35944444444445,114.59555555555555,322.3 +159.4088888888889,-116.42222222222222,120.89999999999999,159.4088888888889,114.63111111111111,322.40000000000003 +159.45833333333334,-116.45833333333333,120.9375,159.45833333333334,114.66666666666667,322.5 +159.50777777777776,-116.49444444444444,120.975,159.50777777777776,114.70222222222222,322.6 +159.5572222222222,-116.53055555555555,121.01249999999999,159.5572222222222,114.73777777777778,322.70000000000005 +159.60666666666665,-116.56666666666665,121.05,159.60666666666665,114.77333333333333,322.8 +159.6561111111111,-116.60277777777776,121.08749999999999,159.6561111111111,114.80888888888889,322.90000000000003 +159.70555555555555,-116.63888888888887,121.125,159.70555555555555,114.84444444444445,323.0 +159.755,-116.67499999999998,121.1625,159.755,114.88,323.1 +159.80444444444444,-116.7111111111111,121.19999999999999,159.80444444444444,114.91555555555556,323.20000000000005 +159.8538888888889,-116.7472222222222,121.2375,159.8538888888889,114.95111111111112,323.3 +159.90333333333334,-116.78333333333332,121.27499999999999,159.90333333333334,114.98666666666666,323.40000000000003 +159.95277777777778,-116.81944444444443,121.3125,159.95277777777778,115.02222222222223,323.5 +160.00222222222223,-116.85555555555554,121.35,160.00222222222223,115.05777777777777,323.6 +160.05166666666668,-116.89166666666665,121.38749999999999,160.05166666666668,115.09333333333333,323.70000000000005 +160.1011111111111,-116.92777777777776,121.425,160.1011111111111,115.1288888888889,323.8 +160.15055555555554,-116.96388888888887,121.46249999999999,160.15055555555554,115.16444444444444,323.90000000000003 +160.2,-116.99999999999999,121.5,160.2,115.2,324.0 +160.24944444444444,-117.0361111111111,121.5375,160.24944444444444,115.23555555555555,324.1 +160.29888888888888,-117.07222222222221,121.57499999999999,160.29888888888888,115.27111111111111,324.20000000000005 +160.34833333333333,-117.10833333333332,121.6125,160.34833333333333,115.30666666666667,324.3 +160.39777777777778,-117.14444444444443,121.64999999999999,160.39777777777778,115.34222222222222,324.40000000000003 +160.44722222222222,-117.18055555555554,121.6875,160.44722222222222,115.37777777777778,324.5 +160.49666666666667,-117.21666666666665,121.725,160.49666666666667,115.41333333333333,324.6 +160.54611111111112,-117.25277777777777,121.76249999999999,160.54611111111112,115.44888888888889,324.70000000000005 +160.59555555555556,-117.28888888888888,121.8,160.59555555555556,115.48444444444445,324.8 +160.645,-117.32499999999999,121.83749999999999,160.645,115.52,324.90000000000003 +160.69444444444443,-117.3611111111111,121.875,160.69444444444443,115.55555555555556,325.0 +160.74388888888888,-117.39722222222221,121.9125,160.74388888888888,115.5911111111111,325.1 +160.79333333333332,-117.43333333333332,121.94999999999999,160.79333333333332,115.62666666666667,325.20000000000005 +160.84277777777777,-117.46944444444443,121.9875,160.84277777777777,115.66222222222223,325.3 +160.89222222222222,-117.50555555555555,122.02499999999999,160.89222222222222,115.69777777777777,325.40000000000003 +160.94166666666666,-117.54166666666666,122.0625,160.94166666666666,115.73333333333333,325.5 +160.9911111111111,-117.57777777777777,122.1,160.9911111111111,115.7688888888889,325.6 +161.04055555555556,-117.61388888888888,122.13749999999999,161.04055555555556,115.80444444444444,325.70000000000005 +161.09,-117.64999999999999,122.175,161.09,115.84,325.8 +161.13944444444445,-117.6861111111111,122.21249999999999,161.13944444444445,115.87555555555555,325.90000000000003 +161.1888888888889,-117.72222222222221,122.25,161.1888888888889,115.91111111111111,326.0 +161.23833333333334,-117.75833333333333,122.2875,161.23833333333334,115.94666666666667,326.1 +161.28777777777776,-117.79444444444444,122.32499999999999,161.28777777777776,115.98222222222222,326.20000000000005 +161.3372222222222,-117.83055555555555,122.3625,161.3372222222222,116.01777777777778,326.3 +161.38666666666666,-117.86666666666666,122.39999999999999,161.38666666666666,116.05333333333333,326.40000000000003 +161.4361111111111,-117.90277777777777,122.4375,161.4361111111111,116.08888888888889,326.5 +161.48555555555555,-117.93888888888888,122.475,161.48555555555555,116.12444444444445,326.6 +161.535,-117.975,122.51249999999999,161.535,116.16,326.70000000000005 +161.58444444444444,-118.0111111111111,122.55,161.58444444444444,116.19555555555556,326.8 +161.6338888888889,-118.04722222222222,122.58749999999999,161.6338888888889,116.2311111111111,326.90000000000003 +161.68333333333334,-118.08333333333333,122.625,161.68333333333334,116.26666666666667,327.0 +161.73277777777778,-118.11944444444444,122.6625,161.73277777777778,116.30222222222223,327.1 +161.78222222222223,-118.15555555555555,122.69999999999999,161.78222222222223,116.33777777777777,327.20000000000005 +161.83166666666668,-118.19166666666665,122.7375,161.83166666666668,116.37333333333333,327.3 +161.8811111111111,-118.22777777777776,122.77499999999999,161.8811111111111,116.40888888888888,327.40000000000003 +161.93055555555554,-118.26388888888887,122.8125,161.93055555555554,116.44444444444444,327.5 +161.98,-118.29999999999998,122.85,161.98,116.48,327.6 +162.02944444444444,-118.3361111111111,122.88749999999999,162.02944444444444,116.51555555555555,327.70000000000005 +162.07888888888888,-118.3722222222222,122.925,162.07888888888888,116.55111111111111,327.8 +162.12833333333333,-118.40833333333332,122.96249999999999,162.12833333333333,116.58666666666667,327.90000000000003 +162.17777777777778,-118.44444444444443,123.0,162.17777777777778,116.62222222222222,328.0 +162.22722222222222,-118.48055555555554,123.0375,162.22722222222222,116.65777777777778,328.1 +162.27666666666667,-118.51666666666665,123.07499999999999,162.27666666666667,116.69333333333333,328.20000000000005 +162.32611111111112,-118.55277777777776,123.1125,162.32611111111112,116.72888888888889,328.3 +162.37555555555556,-118.58888888888887,123.14999999999999,162.37555555555556,116.76444444444445,328.40000000000003 +162.425,-118.62499999999999,123.1875,162.425,116.8,328.5 +162.47444444444443,-118.6611111111111,123.225,162.47444444444443,116.83555555555556,328.6 +162.52388888888888,-118.69722222222221,123.26249999999999,162.52388888888888,116.8711111111111,328.70000000000005 +162.57333333333332,-118.73333333333332,123.3,162.57333333333332,116.90666666666667,328.8 +162.62277777777777,-118.76944444444443,123.33749999999999,162.62277777777777,116.94222222222223,328.90000000000003 +162.67222222222222,-118.80555555555554,123.375,162.67222222222222,116.97777777777777,329.0 +162.72166666666666,-118.84166666666665,123.4125,162.72166666666666,117.01333333333334,329.1 +162.7711111111111,-118.87777777777777,123.44999999999999,162.7711111111111,117.04888888888888,329.20000000000005 +162.82055555555556,-118.91388888888888,123.4875,162.82055555555556,117.08444444444444,329.3 +162.87,-118.94999999999999,123.52499999999999,162.87,117.12,329.40000000000003 +162.91944444444445,-118.9861111111111,123.5625,162.91944444444445,117.15555555555555,329.5 +162.9688888888889,-119.02222222222221,123.6,162.9688888888889,117.19111111111111,329.6 +163.01833333333332,-119.05833333333332,123.63749999999999,163.01833333333332,117.22666666666666,329.70000000000005 +163.06777777777776,-119.09444444444443,123.675,163.06777777777776,117.26222222222222,329.8 +163.1172222222222,-119.13055555555555,123.71249999999999,163.1172222222222,117.29777777777778,329.90000000000003 +163.16666666666666,-119.16666666666666,123.75,163.16666666666666,117.33333333333333,330.0 +163.2161111111111,-119.20277777777777,123.7875,163.2161111111111,117.36888888888889,330.1 +163.26555555555555,-119.23888888888888,123.82499999999999,163.26555555555555,117.40444444444445,330.20000000000005 +163.315,-119.27499999999999,123.8625,163.315,117.44,330.3 +163.36444444444444,-119.3111111111111,123.89999999999999,163.36444444444444,117.47555555555556,330.40000000000003 +163.4138888888889,-119.34722222222221,123.9375,163.4138888888889,117.5111111111111,330.5 +163.46333333333334,-119.38333333333333,123.975,163.46333333333334,117.54666666666667,330.6 +163.51277777777779,-119.41944444444444,124.01249999999999,163.51277777777779,117.58222222222223,330.70000000000005 +163.56222222222223,-119.45555555555555,124.05,163.56222222222223,117.61777777777777,330.8 +163.61166666666665,-119.49166666666666,124.08749999999999,163.61166666666665,117.65333333333334,330.90000000000003 +163.6611111111111,-119.52777777777777,124.125,163.6611111111111,117.68888888888888,331.0 +163.71055555555554,-119.56388888888888,124.1625,163.71055555555554,117.72444444444444,331.1 +163.76,-119.6,124.19999999999999,163.76,117.76,331.20000000000005 +163.80944444444444,-119.6361111111111,124.2375,163.80944444444444,117.79555555555555,331.3 +163.85888888888888,-119.67222222222222,124.27499999999999,163.85888888888888,117.83111111111111,331.40000000000003 +163.90833333333333,-119.70833333333333,124.3125,163.90833333333333,117.86666666666666,331.5 +163.95777777777778,-119.74444444444444,124.35,163.95777777777778,117.90222222222222,331.6 +164.00722222222223,-119.78055555555554,124.38749999999999,164.00722222222223,117.93777777777778,331.70000000000005 +164.05666666666667,-119.81666666666665,124.425,164.05666666666667,117.97333333333333,331.8 +164.10611111111112,-119.85277777777776,124.46249999999999,164.10611111111112,118.00888888888889,331.90000000000003 +164.15555555555557,-119.88888888888887,124.5,164.15555555555557,118.04444444444445,332.0 +164.20499999999998,-119.92499999999998,124.5375,164.20499999999998,118.08,332.1 +164.25444444444443,-119.9611111111111,124.57499999999999,164.25444444444443,118.11555555555556,332.20000000000005 +164.30388888888888,-119.9972222222222,124.6125,164.30388888888888,118.1511111111111,332.3 +164.35333333333332,-120.03333333333332,124.64999999999999,164.35333333333332,118.18666666666667,332.40000000000003 +164.40277777777777,-120.06944444444443,124.6875,164.40277777777777,118.22222222222223,332.5 +164.45222222222222,-120.10555555555554,124.725,164.45222222222222,118.25777777777778,332.6 +164.50166666666667,-120.14166666666665,124.76249999999999,164.50166666666667,118.29333333333334,332.70000000000005 +164.5511111111111,-120.17777777777776,124.8,164.5511111111111,118.32888888888888,332.8 +164.60055555555556,-120.21388888888887,124.83749999999999,164.60055555555556,118.36444444444444,332.90000000000003 +164.65,-120.24999999999999,124.875,164.65,118.4,333.0 +164.69944444444445,-120.2861111111111,124.9125,164.69944444444445,118.43555555555555,333.1 +164.7488888888889,-120.32222222222221,124.94999999999999,164.7488888888889,118.47111111111111,333.20000000000005 +164.79833333333332,-120.35833333333332,124.9875,164.79833333333332,118.50666666666666,333.3 +164.84777777777776,-120.39444444444443,125.02499999999999,164.84777777777776,118.54222222222222,333.40000000000003 +164.8972222222222,-120.43055555555554,125.0625,164.8972222222222,118.57777777777778,333.5 +164.94666666666666,-120.46666666666665,125.1,164.94666666666666,118.61333333333333,333.6 +164.9961111111111,-120.50277777777777,125.13749999999999,164.9961111111111,118.64888888888889,333.70000000000005 +165.04555555555555,-120.53888888888888,125.175,165.04555555555555,118.68444444444444,333.8 +165.095,-120.57499999999999,125.21249999999999,165.095,118.72,333.90000000000003 +165.14444444444445,-120.6111111111111,125.25,165.14444444444445,118.75555555555556,334.0 +165.1938888888889,-120.64722222222221,125.2875,165.1938888888889,118.7911111111111,334.1 +165.24333333333334,-120.68333333333332,125.32499999999999,165.24333333333334,118.82666666666667,334.20000000000005 +165.2927777777778,-120.71944444444443,125.3625,165.2927777777778,118.86222222222223,334.3 +165.34222222222223,-120.75555555555555,125.39999999999999,165.34222222222223,118.89777777777778,334.40000000000003 +165.39166666666665,-120.79166666666666,125.4375,165.39166666666665,118.93333333333334,334.5 +165.4411111111111,-120.82777777777777,125.475,165.4411111111111,118.96888888888888,334.6 +165.49055555555555,-120.86388888888888,125.51249999999999,165.49055555555555,119.00444444444445,334.70000000000005 +165.54,-120.89999999999999,125.55,165.54,119.04,334.8 +165.58944444444444,-120.9361111111111,125.58749999999999,165.58944444444444,119.07555555555555,334.90000000000003 +165.63888888888889,-120.97222222222221,125.625,165.63888888888889,119.11111111111111,335.0 +165.68833333333333,-121.00833333333333,125.6625,165.68833333333333,119.14666666666666,335.1 +165.73777777777778,-121.04444444444444,125.69999999999999,165.73777777777778,119.18222222222222,335.20000000000005 +165.78722222222223,-121.08055555555555,125.7375,165.78722222222223,119.21777777777778,335.3 +165.83666666666667,-121.11666666666666,125.77499999999999,165.83666666666667,119.25333333333333,335.40000000000003 +165.88611111111112,-121.15277777777777,125.8125,165.88611111111112,119.28888888888889,335.5 +165.93555555555557,-121.18888888888888,125.85,165.93555555555557,119.32444444444444,335.6 +165.98499999999999,-121.225,125.88749999999999,165.98499999999999,119.36,335.70000000000005 +166.03444444444443,-121.2611111111111,125.925,166.03444444444443,119.39555555555556,335.8 +166.08388888888888,-121.29722222222222,125.96249999999999,166.08388888888888,119.43111111111111,335.90000000000003 +166.13333333333333,-121.33333333333333,126.0,166.13333333333333,119.46666666666667,336.0 +166.18277777777777,-121.36944444444444,126.0375,166.18277777777777,119.50222222222222,336.1 +166.23222222222222,-121.40555555555554,126.07499999999999,166.23222222222222,119.53777777777778,336.20000000000005 +166.28166666666667,-121.44166666666665,126.1125,166.28166666666667,119.57333333333334,336.3 +166.3311111111111,-121.47777777777776,126.14999999999999,166.3311111111111,119.60888888888888,336.40000000000003 +166.38055555555556,-121.51388888888887,126.1875,166.38055555555556,119.64444444444445,336.5 +166.43,-121.54999999999998,126.225,166.43,119.68,336.6 +166.47944444444445,-121.5861111111111,126.26249999999999,166.47944444444445,119.71555555555555,336.70000000000005 +166.52888888888887,-121.6222222222222,126.3,166.52888888888887,119.75111111111111,336.8 +166.57833333333332,-121.65833333333332,126.33749999999999,166.57833333333332,119.78666666666666,336.90000000000003 +166.62777777777777,-121.69444444444443,126.375,166.62777777777777,119.82222222222222,337.0 +166.6772222222222,-121.73055555555554,126.4125,166.6772222222222,119.85777777777778,337.1 +166.72666666666666,-121.76666666666665,126.44999999999999,166.72666666666666,119.89333333333333,337.20000000000005 +166.7761111111111,-121.80277777777776,126.4875,166.7761111111111,119.92888888888889,337.3 +166.82555555555555,-121.83888888888887,126.52499999999999,166.82555555555555,119.96444444444444,337.40000000000003 +166.875,-121.87499999999999,126.5625,166.875,120.0,337.5 +166.92444444444445,-121.9111111111111,126.6,166.92444444444445,120.03555555555556,337.6 +166.9738888888889,-121.94722222222221,126.63749999999999,166.9738888888889,120.07111111111111,337.70000000000005 +167.02333333333334,-121.98333333333332,126.675,167.02333333333334,120.10666666666667,337.8 +167.0727777777778,-122.01944444444443,126.71249999999999,167.0727777777778,120.14222222222222,337.90000000000003 +167.1222222222222,-122.05555555555554,126.75,167.1222222222222,120.17777777777778,338.0 +167.17166666666665,-122.09166666666665,126.7875,167.17166666666665,120.21333333333334,338.1 +167.2211111111111,-122.12777777777777,126.82499999999999,167.2211111111111,120.24888888888889,338.20000000000005 +167.27055555555555,-122.16388888888888,126.8625,167.27055555555555,120.28444444444445,338.3 +167.32,-122.19999999999999,126.89999999999999,167.32,120.32,338.40000000000003 +167.36944444444444,-122.2361111111111,126.9375,167.36944444444444,120.35555555555555,338.5 +167.4188888888889,-122.27222222222221,126.975,167.4188888888889,120.39111111111112,338.6 +167.46833333333333,-122.30833333333332,127.01249999999999,167.46833333333333,120.42666666666666,338.70000000000005 +167.51777777777778,-122.34444444444443,127.05,167.51777777777778,120.46222222222222,338.8 +167.56722222222223,-122.38055555555555,127.08749999999999,167.56722222222223,120.49777777777778,338.90000000000003 +167.61666666666667,-122.41666666666666,127.125,167.61666666666667,120.53333333333333,339.0 +167.66611111111112,-122.45277777777777,127.1625,167.66611111111112,120.56888888888889,339.1 +167.71555555555554,-122.48888888888888,127.19999999999999,167.71555555555554,120.60444444444444,339.20000000000005 +167.765,-122.52499999999999,127.2375,167.765,120.64,339.3 +167.81444444444443,-122.5611111111111,127.27499999999999,167.81444444444443,120.67555555555556,339.40000000000003 +167.86388888888888,-122.59722222222221,127.3125,167.86388888888888,120.71111111111111,339.5 +167.91333333333333,-122.63333333333333,127.35,167.91333333333333,120.74666666666667,339.6 +167.96277777777777,-122.66944444444444,127.38749999999999,167.96277777777777,120.78222222222222,339.70000000000005 +168.01222222222222,-122.70555555555555,127.425,168.01222222222222,120.81777777777778,339.8 +168.06166666666667,-122.74166666666666,127.46249999999999,168.06166666666667,120.85333333333334,339.90000000000003 +168.11111111111111,-122.77777777777777,127.5,168.11111111111111,120.88888888888889,340.0 +168.16055555555556,-122.81388888888888,127.5375,168.16055555555556,120.92444444444445,340.1 +168.21,-122.85,127.57499999999999,168.21,120.96,340.20000000000005 +168.25944444444445,-122.8861111111111,127.6125,168.25944444444445,120.99555555555555,340.3 +168.30888888888887,-122.92222222222222,127.64999999999999,168.30888888888887,121.03111111111112,340.40000000000003 +168.35833333333332,-122.95833333333333,127.6875,168.35833333333332,121.06666666666666,340.5 +168.40777777777777,-122.99444444444443,127.725,168.40777777777777,121.10222222222222,340.6 +168.4572222222222,-123.03055555555554,127.76249999999999,168.4572222222222,121.13777777777777,340.70000000000005 +168.50666666666666,-123.06666666666665,127.8,168.50666666666666,121.17333333333333,340.8 +168.5561111111111,-123.10277777777776,127.83749999999999,168.5561111111111,121.2088888888889,340.90000000000003 +168.60555555555555,-123.13888888888887,127.875,168.60555555555555,121.24444444444444,341.0 +168.655,-123.17499999999998,127.9125,168.655,121.28,341.1 +168.70444444444445,-123.2111111111111,127.94999999999999,168.70444444444445,121.31555555555556,341.20000000000005 +168.7538888888889,-123.2472222222222,127.9875,168.7538888888889,121.35111111111111,341.3 +168.80333333333334,-123.28333333333332,128.025,168.80333333333334,121.38666666666667,341.40000000000003 +168.8527777777778,-123.31944444444443,128.0625,168.8527777777778,121.42222222222222,341.5 +168.9022222222222,-123.35555555555554,128.1,168.9022222222222,121.45777777777778,341.6 +168.95166666666665,-123.39166666666665,128.1375,168.95166666666665,121.49333333333334,341.70000000000005 +169.0011111111111,-123.42777777777776,128.17499999999998,169.0011111111111,121.52888888888889,341.8 +169.05055555555555,-123.46388888888887,128.2125,169.05055555555555,121.56444444444445,341.90000000000003 +169.1,-123.49999999999999,128.25,169.1,121.6,342.0 +169.14944444444444,-123.5361111111111,128.2875,169.14944444444444,121.63555555555556,342.1 +169.1988888888889,-123.57222222222221,128.325,169.1988888888889,121.67111111111112,342.20000000000005 +169.24833333333333,-123.60833333333332,128.36249999999998,169.24833333333333,121.70666666666666,342.3 +169.29777777777778,-123.64444444444443,128.4,169.29777777777778,121.74222222222222,342.40000000000003 +169.34722222222223,-123.68055555555554,128.4375,169.34722222222223,121.77777777777777,342.5 +169.39666666666668,-123.71666666666665,128.475,169.39666666666668,121.81333333333333,342.6 +169.44611111111112,-123.75277777777777,128.5125,169.44611111111112,121.8488888888889,342.70000000000005 +169.49555555555554,-123.78888888888888,128.54999999999998,169.49555555555554,121.88444444444444,342.8 +169.545,-123.82499999999999,128.5875,169.545,121.92,342.90000000000003 +169.59444444444443,-123.8611111111111,128.625,169.59444444444443,121.95555555555555,343.0 +169.64388888888888,-123.89722222222221,128.6625,169.64388888888888,121.99111111111111,343.1 +169.69333333333333,-123.93333333333332,128.7,169.69333333333333,122.02666666666667,343.20000000000005 +169.74277777777777,-123.96944444444443,128.73749999999998,169.74277777777777,122.06222222222222,343.3 +169.79222222222222,-124.00555555555555,128.775,169.79222222222222,122.09777777777778,343.40000000000003 +169.84166666666667,-124.04166666666666,128.8125,169.84166666666667,122.13333333333334,343.5 +169.89111111111112,-124.07777777777777,128.85,169.89111111111112,122.16888888888889,343.6 +169.94055555555556,-124.11388888888888,128.8875,169.94055555555556,122.20444444444445,343.70000000000005 +169.99,-124.14999999999999,128.92499999999998,169.99,122.24,343.8 +170.03944444444443,-124.1861111111111,128.9625,170.03944444444443,122.27555555555556,343.90000000000003 +170.08888888888887,-124.22222222222221,129.0,170.08888888888887,122.31111111111112,344.0 +170.13833333333332,-124.25833333333333,129.0375,170.13833333333332,122.34666666666666,344.1 +170.18777777777777,-124.29444444444444,129.075,170.18777777777777,122.38222222222223,344.20000000000005 +170.23722222222221,-124.33055555555555,129.11249999999998,170.23722222222221,122.41777777777777,344.3 +170.28666666666666,-124.36666666666666,129.15,170.28666666666666,122.45333333333333,344.40000000000003 +170.3361111111111,-124.40277777777777,129.1875,170.3361111111111,122.4888888888889,344.5 +170.38555555555556,-124.43888888888888,129.225,170.38555555555556,122.52444444444444,344.6 +170.435,-124.475,129.2625,170.435,122.56,344.70000000000005 +170.48444444444445,-124.5111111111111,129.29999999999998,170.48444444444445,122.59555555555555,344.8 +170.5338888888889,-124.54722222222222,129.3375,170.5338888888889,122.63111111111111,344.90000000000003 +170.58333333333334,-124.58333333333333,129.375,170.58333333333334,122.66666666666667,345.0 +170.63277777777776,-124.61944444444443,129.4125,170.63277777777776,122.70222222222222,345.1 +170.6822222222222,-124.65555555555554,129.45,170.6822222222222,122.73777777777778,345.20000000000005 +170.73166666666665,-124.69166666666665,129.48749999999998,170.73166666666665,122.77333333333333,345.3 +170.7811111111111,-124.72777777777776,129.525,170.7811111111111,122.80888888888889,345.40000000000003 +170.83055555555555,-124.76388888888887,129.5625,170.83055555555555,122.84444444444445,345.5 +170.88,-124.79999999999998,129.6,170.88,122.88,345.6 +170.92944444444444,-124.8361111111111,129.6375,170.92944444444444,122.91555555555556,345.70000000000005 +170.9788888888889,-124.8722222222222,129.67499999999998,170.9788888888889,122.95111111111112,345.8 +171.02833333333334,-124.90833333333332,129.7125,171.02833333333334,122.98666666666666,345.90000000000003 +171.07777777777778,-124.94444444444443,129.75,171.07777777777778,123.02222222222223,346.0 +171.12722222222223,-124.98055555555554,129.7875,171.12722222222223,123.05777777777777,346.1 +171.17666666666668,-125.01666666666665,129.825,171.17666666666668,123.09333333333333,346.20000000000005 +171.2261111111111,-125.05277777777776,129.86249999999998,171.2261111111111,123.1288888888889,346.3 +171.27555555555554,-125.08888888888887,129.9,171.27555555555554,123.16444444444444,346.40000000000003 +171.325,-125.12499999999999,129.9375,171.325,123.2,346.5 +171.37444444444444,-125.1611111111111,129.975,171.37444444444444,123.23555555555555,346.6 +171.42388888888888,-125.19722222222221,130.0125,171.42388888888888,123.27111111111111,346.70000000000005 +171.47333333333333,-125.23333333333332,130.04999999999998,171.47333333333333,123.30666666666667,346.8 +171.52277777777778,-125.26944444444443,130.0875,171.52277777777778,123.34222222222222,346.90000000000003 +171.57222222222222,-125.30555555555554,130.125,171.57222222222222,123.37777777777778,347.0 +171.62166666666667,-125.34166666666665,130.1625,171.62166666666667,123.41333333333333,347.1 +171.67111111111112,-125.37777777777777,130.2,171.67111111111112,123.44888888888889,347.20000000000005 +171.72055555555556,-125.41388888888888,130.23749999999998,171.72055555555556,123.48444444444445,347.3 +171.77,-125.44999999999999,130.275,171.77,123.52,347.40000000000003 +171.81944444444443,-125.4861111111111,130.3125,171.81944444444443,123.55555555555556,347.5 +171.86888888888888,-125.52222222222221,130.35,171.86888888888888,123.5911111111111,347.6 +171.91833333333332,-125.55833333333332,130.3875,171.91833333333332,123.62666666666667,347.70000000000005 +171.96777777777777,-125.59444444444443,130.42499999999998,171.96777777777777,123.66222222222223,347.8 +172.01722222222222,-125.63055555555555,130.4625,172.01722222222222,123.69777777777777,347.90000000000003 +172.06666666666666,-125.66666666666666,130.5,172.06666666666666,123.73333333333333,348.0 +172.1161111111111,-125.70277777777777,130.5375,172.1161111111111,123.7688888888889,348.1 +172.16555555555556,-125.73888888888888,130.575,172.16555555555556,123.80444444444444,348.20000000000005 +172.215,-125.77499999999999,130.61249999999998,172.215,123.84,348.3 +172.26444444444445,-125.8111111111111,130.65,172.26444444444445,123.87555555555555,348.40000000000003 +172.3138888888889,-125.84722222222221,130.6875,172.3138888888889,123.91111111111111,348.5 +172.36333333333334,-125.88333333333333,130.725,172.36333333333334,123.94666666666667,348.6 +172.41277777777776,-125.91944444444444,130.7625,172.41277777777776,123.98222222222222,348.70000000000005 +172.4622222222222,-125.95555555555555,130.79999999999998,172.4622222222222,124.01777777777778,348.8 +172.51166666666666,-125.99166666666666,130.8375,172.51166666666666,124.05333333333333,348.90000000000003 +172.5611111111111,-126.02777777777777,130.875,172.5611111111111,124.08888888888889,349.0 +172.61055555555555,-126.06388888888888,130.9125,172.61055555555555,124.12444444444445,349.1 +172.66,-126.1,130.95,172.66,124.16,349.20000000000005 +172.70944444444444,-126.1361111111111,130.98749999999998,172.70944444444444,124.19555555555556,349.3 +172.7588888888889,-126.17222222222222,131.025,172.7588888888889,124.2311111111111,349.40000000000003 +172.80833333333334,-126.20833333333331,131.0625,172.80833333333334,124.26666666666667,349.5 +172.85777777777778,-126.24444444444443,131.1,172.85777777777778,124.30222222222223,349.6 +172.90722222222223,-126.28055555555554,131.1375,172.90722222222223,124.33777777777777,349.70000000000005 +172.95666666666668,-126.31666666666665,131.17499999999998,172.95666666666668,124.37333333333333,349.8 +173.0061111111111,-126.35277777777776,131.2125,173.0061111111111,124.40888888888888,349.90000000000003 +173.05555555555554,-126.38888888888887,131.25,173.05555555555554,124.44444444444444,350.0 +173.105,-126.42499999999998,131.2875,173.105,124.48,350.1 +173.15444444444444,-126.4611111111111,131.325,173.15444444444444,124.51555555555555,350.20000000000005 +173.20388888888888,-126.4972222222222,131.36249999999998,173.20388888888888,124.55111111111111,350.3 +173.25333333333333,-126.53333333333332,131.4,173.25333333333333,124.58666666666667,350.40000000000003 +173.30277777777778,-126.56944444444443,131.4375,173.30277777777778,124.62222222222222,350.5 +173.35222222222222,-126.60555555555554,131.475,173.35222222222222,124.65777777777778,350.6 +173.40166666666667,-126.64166666666665,131.5125,173.40166666666667,124.69333333333333,350.70000000000005 +173.45111111111112,-126.67777777777776,131.54999999999998,173.45111111111112,124.72888888888889,350.8 +173.50055555555556,-126.71388888888887,131.5875,173.50055555555556,124.76444444444445,350.90000000000003 +173.55,-126.74999999999999,131.625,173.55,124.8,351.0 +173.59944444444443,-126.7861111111111,131.6625,173.59944444444443,124.83555555555556,351.1 +173.64888888888888,-126.82222222222221,131.7,173.64888888888888,124.8711111111111,351.20000000000005 +173.69833333333332,-126.85833333333332,131.73749999999998,173.69833333333332,124.90666666666667,351.3 +173.74777777777777,-126.89444444444443,131.775,173.74777777777777,124.94222222222223,351.40000000000003 +173.79722222222222,-126.93055555555554,131.8125,173.79722222222222,124.97777777777777,351.5 +173.84666666666666,-126.96666666666665,131.85,173.84666666666666,125.01333333333334,351.6 +173.8961111111111,-127.00277777777777,131.8875,173.8961111111111,125.04888888888888,351.70000000000005 +173.94555555555556,-127.03888888888888,131.92499999999998,173.94555555555556,125.08444444444444,351.8 +173.995,-127.07499999999999,131.9625,173.995,125.12,351.90000000000003 +174.04444444444445,-127.1111111111111,132.0,174.04444444444445,125.15555555555555,352.0 +174.0938888888889,-127.14722222222221,132.0375,174.0938888888889,125.19111111111111,352.1 +174.14333333333332,-127.18333333333332,132.075,174.14333333333332,125.22666666666666,352.20000000000005 +174.19277777777776,-127.21944444444443,132.11249999999998,174.19277777777776,125.26222222222222,352.3 +174.2422222222222,-127.25555555555555,132.15,174.2422222222222,125.29777777777778,352.40000000000003 +174.29166666666666,-127.29166666666666,132.1875,174.29166666666666,125.33333333333333,352.5 +174.3411111111111,-127.32777777777777,132.225,174.3411111111111,125.36888888888889,352.6 +174.39055555555555,-127.36388888888888,132.2625,174.39055555555555,125.40444444444445,352.70000000000005 +174.44,-127.39999999999999,132.29999999999998,174.44,125.44,352.8 +174.48944444444444,-127.4361111111111,132.3375,174.48944444444444,125.47555555555556,352.90000000000003 +174.5388888888889,-127.47222222222221,132.375,174.5388888888889,125.5111111111111,353.0 +174.58833333333334,-127.50833333333333,132.4125,174.58833333333334,125.54666666666667,353.1 +174.63777777777779,-127.54444444444444,132.45,174.63777777777779,125.58222222222223,353.20000000000005 +174.68722222222223,-127.58055555555555,132.48749999999998,174.68722222222223,125.61777777777777,353.3 +174.73666666666665,-127.61666666666666,132.525,174.73666666666665,125.65333333333334,353.40000000000003 +174.7861111111111,-127.65277777777777,132.5625,174.7861111111111,125.68888888888888,353.5 +174.83555555555554,-127.68888888888888,132.6,174.83555555555554,125.72444444444444,353.6 +174.885,-127.725,132.6375,174.885,125.76,353.70000000000005 +174.93444444444444,-127.7611111111111,132.67499999999998,174.93444444444444,125.79555555555555,353.8 +174.98388888888888,-127.79722222222222,132.7125,174.98388888888888,125.83111111111111,353.90000000000003 +175.03333333333333,-127.83333333333331,132.75,175.03333333333333,125.86666666666666,354.0 +175.08277777777778,-127.86944444444443,132.7875,175.08277777777778,125.90222222222222,354.1 +175.13222222222223,-127.90555555555554,132.825,175.13222222222223,125.93777777777778,354.20000000000005 +175.18166666666667,-127.94166666666665,132.86249999999998,175.18166666666667,125.97333333333333,354.3 +175.23111111111112,-127.97777777777776,132.9,175.23111111111112,126.00888888888889,354.40000000000003 +175.28055555555557,-128.01388888888889,132.9375,175.28055555555557,126.04444444444445,354.5 +175.32999999999998,-128.04999999999998,132.975,175.32999999999998,126.08,354.6 +175.37944444444443,-128.0861111111111,133.0125,175.37944444444443,126.11555555555556,354.70000000000005 +175.42888888888888,-128.1222222222222,133.04999999999998,175.42888888888888,126.1511111111111,354.8 +175.47833333333332,-128.15833333333333,133.0875,175.47833333333332,126.18666666666667,354.90000000000003 +175.52777777777777,-128.19444444444443,133.125,175.52777777777777,126.22222222222223,355.0 +175.57722222222222,-128.23055555555555,133.1625,175.57722222222222,126.25777777777778,355.1 +175.62666666666667,-128.26666666666665,133.2,175.62666666666667,126.29333333333334,355.20000000000005 +175.6761111111111,-128.30277777777778,133.23749999999998,175.6761111111111,126.32888888888888,355.3 +175.72555555555556,-128.33888888888887,133.275,175.72555555555556,126.36444444444444,355.40000000000003 +175.775,-128.375,133.3125,175.775,126.4,355.5 +175.82444444444445,-128.4111111111111,133.35,175.82444444444445,126.43555555555555,355.6 +175.8738888888889,-128.44722222222222,133.3875,175.8738888888889,126.47111111111111,355.70000000000005 +175.92333333333332,-128.48333333333332,133.42499999999998,175.92333333333332,126.50666666666666,355.8 +175.97277777777776,-128.51944444444445,133.4625,175.97277777777776,126.54222222222222,355.90000000000003 +176.0222222222222,-128.55555555555554,133.5,176.0222222222222,126.57777777777778,356.0 +176.07166666666666,-128.59166666666667,133.5375,176.07166666666666,126.61333333333333,356.1 +176.1211111111111,-128.62777777777777,133.575,176.1211111111111,126.64888888888889,356.20000000000005 +176.17055555555555,-128.66388888888886,133.61249999999998,176.17055555555555,126.68444444444444,356.3 +176.22,-128.7,133.65,176.22,126.72,356.40000000000003 +176.26944444444445,-128.7361111111111,133.6875,176.26944444444445,126.75555555555556,356.5 +176.3188888888889,-128.7722222222222,133.725,176.3188888888889,126.7911111111111,356.6 +176.36833333333334,-128.8083333333333,133.7625,176.36833333333334,126.82666666666667,356.70000000000005 +176.4177777777778,-128.84444444444443,133.79999999999998,176.4177777777778,126.86222222222223,356.8 +176.46722222222223,-128.88055555555553,133.8375,176.46722222222223,126.89777777777778,356.90000000000003 +176.51666666666665,-128.91666666666666,133.875,176.51666666666665,126.93333333333334,357.0 +176.5661111111111,-128.95277777777775,133.9125,176.5661111111111,126.96888888888888,357.1 +176.61555555555555,-128.98888888888888,133.95,176.61555555555555,127.00444444444445,357.20000000000005 +176.665,-129.02499999999998,133.98749999999998,176.665,127.04,357.3 +176.71444444444444,-129.0611111111111,134.025,176.71444444444444,127.07555555555555,357.40000000000003 +176.76388888888889,-129.0972222222222,134.0625,176.76388888888889,127.11111111111111,357.5 +176.81333333333333,-129.13333333333333,134.1,176.81333333333333,127.14666666666666,357.6 +176.86277777777778,-129.16944444444442,134.1375,176.86277777777778,127.18222222222222,357.70000000000005 +176.91222222222223,-129.20555555555555,134.17499999999998,176.91222222222223,127.21777777777778,357.8 +176.96166666666667,-129.24166666666665,134.2125,176.96166666666667,127.25333333333333,357.90000000000003 +177.01111111111112,-129.27777777777777,134.25,177.01111111111112,127.28888888888889,358.0 +177.06055555555557,-129.31388888888887,134.2875,177.06055555555557,127.32444444444444,358.1 +177.10999999999999,-129.35,134.325,177.10999999999999,127.36,358.20000000000005 +177.15944444444443,-129.3861111111111,134.36249999999998,177.15944444444443,127.39555555555556,358.3 +177.20888888888888,-129.42222222222222,134.4,177.20888888888888,127.43111111111111,358.40000000000003 +177.25833333333333,-129.45833333333331,134.4375,177.25833333333333,127.46666666666667,358.5 +177.30777777777777,-129.49444444444444,134.475,177.30777777777777,127.50222222222222,358.6 +177.35722222222222,-129.53055555555554,134.5125,177.35722222222222,127.53777777777778,358.70000000000005 +177.40666666666667,-129.56666666666666,134.54999999999998,177.40666666666667,127.57333333333334,358.8 +177.4561111111111,-129.60277777777776,134.5875,177.4561111111111,127.60888888888888,358.90000000000003 +177.50555555555556,-129.63888888888889,134.625,177.50555555555556,127.64444444444445,359.0 +177.555,-129.67499999999998,134.6625,177.555,127.68,359.1 +177.60444444444445,-129.7111111111111,134.7,177.60444444444445,127.71555555555555,359.20000000000005 +177.65388888888887,-129.7472222222222,134.73749999999998,177.65388888888887,127.75111111111111,359.3 +177.70333333333332,-129.78333333333333,134.775,177.70333333333332,127.78666666666666,359.40000000000003 +177.75277777777777,-129.81944444444443,134.8125,177.75277777777777,127.82222222222222,359.5 +177.8022222222222,-129.85555555555555,134.85,177.8022222222222,127.85777777777778,359.6 +177.85166666666666,-129.89166666666665,134.8875,177.85166666666666,127.89333333333333,359.70000000000005 +177.9011111111111,-129.92777777777778,134.92499999999998,177.9011111111111,127.92888888888889,359.8 +177.95055555555555,-129.96388888888887,134.9625,177.95055555555555,127.96444444444444,359.90000000000003 +178,-130,135,178,128,360 diff --git a/rm_arm_control/data/RM75_canfd_data.txt b/rm_arm_control/data/RM75_canfd_data.txt new file mode 100644 index 0000000..846a0a9 --- /dev/null +++ b/rm_arm_control/data/RM75_canfd_data.txt @@ -0,0 +1,3600 @@ +0.049444444444444444,0.03611111111111111,0.049444444444444444,0.0375,0.049444444444444444,0.035555555555555556,0.1 +0.09888888888888889,0.07222222222222222,0.09888888888888889,0.075,0.09888888888888889,0.07111111111111111,0.2 +0.14833333333333332,0.10833333333333332,0.14833333333333332,0.11249999999999999,0.14833333333333332,0.10666666666666666,0.30000000000000004 +0.19777777777777777,0.14444444444444443,0.19777777777777777,0.15,0.19777777777777777,0.14222222222222222,0.4 +0.24722222222222223,0.18055555555555552,0.24722222222222223,0.1875,0.24722222222222223,0.17777777777777778,0.5 +0.29666666666666663,0.21666666666666665,0.29666666666666663,0.22499999999999998,0.29666666666666663,0.21333333333333332,0.6000000000000001 +0.3461111111111111,0.25277777777777777,0.3461111111111111,0.2625,0.3461111111111111,0.24888888888888888,0.7000000000000001 +0.39555555555555555,0.28888888888888886,0.39555555555555555,0.3,0.39555555555555555,0.28444444444444444,0.8 +0.445,0.32499999999999996,0.445,0.33749999999999997,0.445,0.32,0.9 +0.49444444444444446,0.36111111111111105,0.49444444444444446,0.375,0.49444444444444446,0.35555555555555557,1.0 +0.5438888888888889,0.3972222222222222,0.5438888888888889,0.4125,0.5438888888888889,0.39111111111111113,1.1 +0.5933333333333333,0.4333333333333333,0.5933333333333333,0.44999999999999996,0.5933333333333333,0.42666666666666664,1.2000000000000002 +0.6427777777777778,0.4694444444444444,0.6427777777777778,0.4875,0.6427777777777778,0.4622222222222222,1.3 +0.6922222222222222,0.5055555555555555,0.6922222222222222,0.525,0.6922222222222222,0.49777777777777776,1.4000000000000001 +0.7416666666666667,0.5416666666666666,0.7416666666666667,0.5625,0.7416666666666667,0.5333333333333333,1.5 +0.7911111111111111,0.5777777777777777,0.7911111111111111,0.6,0.7911111111111111,0.5688888888888889,1.6 +0.8405555555555555,0.6138888888888888,0.8405555555555555,0.6375,0.8405555555555555,0.6044444444444445,1.7000000000000002 +0.89,0.6499999999999999,0.89,0.6749999999999999,0.89,0.64,1.8 +0.9394444444444444,0.686111111111111,0.9394444444444444,0.7125,0.9394444444444444,0.6755555555555556,1.9000000000000001 +0.9888888888888889,0.7222222222222221,0.9888888888888889,0.75,0.9888888888888889,0.7111111111111111,2.0 +1.0383333333333333,0.7583333333333333,1.0383333333333333,0.7875,1.0383333333333333,0.7466666666666667,2.1 +1.0877777777777777,0.7944444444444444,1.0877777777777777,0.825,1.0877777777777777,0.7822222222222223,2.2 +1.1372222222222221,0.8305555555555555,1.1372222222222221,0.8624999999999999,1.1372222222222221,0.8177777777777778,2.3000000000000003 +1.1866666666666665,0.8666666666666666,1.1866666666666665,0.8999999999999999,1.1866666666666665,0.8533333333333333,2.4000000000000004 +1.2361111111111112,0.9027777777777777,1.2361111111111112,0.9375,1.2361111111111112,0.8888888888888888,2.5 +1.2855555555555556,0.9388888888888888,1.2855555555555556,0.975,1.2855555555555556,0.9244444444444444,2.6 +1.335,0.9749999999999999,1.335,1.0125,1.335,0.96,2.7 +1.3844444444444444,1.011111111111111,1.3844444444444444,1.05,1.3844444444444444,0.9955555555555555,2.8000000000000003 +1.4338888888888888,1.047222222222222,1.4338888888888888,1.0875,1.4338888888888888,1.031111111111111,2.9000000000000004 +1.4833333333333334,1.0833333333333333,1.4833333333333334,1.125,1.4833333333333334,1.0666666666666667,3.0 +1.5327777777777778,1.1194444444444442,1.5327777777777778,1.1624999999999999,1.5327777777777778,1.1022222222222222,3.1 +1.5822222222222222,1.1555555555555554,1.5822222222222222,1.2,1.5822222222222222,1.1377777777777778,3.2 +1.6316666666666666,1.1916666666666667,1.6316666666666666,1.2375,1.6316666666666666,1.1733333333333333,3.3000000000000003 +1.681111111111111,1.2277777777777776,1.681111111111111,1.275,1.681111111111111,1.208888888888889,3.4000000000000004 +1.7305555555555556,1.2638888888888888,1.7305555555555556,1.3125,1.7305555555555556,1.2444444444444445,3.5 +1.78,1.2999999999999998,1.78,1.3499999999999999,1.78,1.28,3.6 +1.8294444444444444,1.336111111111111,1.8294444444444444,1.3875,1.8294444444444444,1.3155555555555556,3.7 +1.8788888888888888,1.372222222222222,1.8788888888888888,1.425,1.8788888888888888,1.3511111111111112,3.8000000000000003 +1.9283333333333332,1.4083333333333332,1.9283333333333332,1.4625,1.9283333333333332,1.3866666666666667,3.9000000000000004 +1.9777777777777779,1.4444444444444442,1.9777777777777779,1.5,1.9777777777777779,1.4222222222222223,4.0 +2.027222222222222,1.4805555555555554,2.027222222222222,1.5374999999999999,2.027222222222222,1.4577777777777778,4.1000000000000005 +2.0766666666666667,1.5166666666666666,2.0766666666666667,1.575,2.0766666666666667,1.4933333333333334,4.2 +2.1261111111111113,1.5527777777777776,2.1261111111111113,1.6125,2.1261111111111113,1.528888888888889,4.3 +2.1755555555555555,1.5888888888888888,2.1755555555555555,1.65,2.1755555555555555,1.5644444444444445,4.4 +2.225,1.6249999999999998,2.225,1.6875,2.225,1.6,4.5 +2.2744444444444443,1.661111111111111,2.2744444444444443,1.7249999999999999,2.2744444444444443,1.6355555555555557,4.6000000000000005 +2.323888888888889,1.697222222222222,2.323888888888889,1.7625,2.323888888888889,1.6711111111111112,4.7 +2.373333333333333,1.7333333333333332,2.373333333333333,1.7999999999999998,2.373333333333333,1.7066666666666666,4.800000000000001 +2.4227777777777777,1.7694444444444444,2.4227777777777777,1.8375,2.4227777777777777,1.7422222222222221,4.9 +2.4722222222222223,1.8055555555555554,2.4722222222222223,1.875,2.4722222222222223,1.7777777777777777,5.0 +2.5216666666666665,1.8416666666666666,2.5216666666666665,1.9124999999999999,2.5216666666666665,1.8133333333333332,5.1000000000000005 +2.571111111111111,1.8777777777777775,2.571111111111111,1.95,2.571111111111111,1.8488888888888888,5.2 +2.6205555555555553,1.9138888888888888,2.6205555555555553,1.9874999999999998,2.6205555555555553,1.8844444444444444,5.300000000000001 +2.67,1.9499999999999997,2.67,2.025,2.67,1.92,5.4 +2.7194444444444446,1.986111111111111,2.7194444444444446,2.0625,2.7194444444444446,1.9555555555555555,5.5 +2.7688888888888887,2.022222222222222,2.7688888888888887,2.1,2.7688888888888887,1.991111111111111,5.6000000000000005 +2.8183333333333334,2.058333333333333,2.8183333333333334,2.1374999999999997,2.8183333333333334,2.026666666666667,5.7 +2.8677777777777775,2.094444444444444,2.8677777777777775,2.175,2.8677777777777775,2.062222222222222,5.800000000000001 +2.917222222222222,2.1305555555555555,2.917222222222222,2.2125,2.917222222222222,2.097777777777778,5.9 +2.966666666666667,2.1666666666666665,2.966666666666667,2.25,2.966666666666667,2.1333333333333333,6.0 +3.016111111111111,2.2027777777777775,3.016111111111111,2.2875,3.016111111111111,2.168888888888889,6.1000000000000005 +3.0655555555555556,2.2388888888888885,3.0655555555555556,2.3249999999999997,3.0655555555555556,2.2044444444444444,6.2 +3.1149999999999998,2.275,3.1149999999999998,2.3625,3.1149999999999998,2.24,6.300000000000001 +3.1644444444444444,2.311111111111111,3.1644444444444444,2.4,3.1644444444444444,2.2755555555555556,6.4 +3.213888888888889,2.347222222222222,3.213888888888889,2.4375,3.213888888888889,2.311111111111111,6.5 +3.263333333333333,2.3833333333333333,3.263333333333333,2.475,3.263333333333333,2.3466666666666667,6.6000000000000005 +3.312777777777778,2.4194444444444443,3.312777777777778,2.5124999999999997,3.312777777777778,2.382222222222222,6.7 +3.362222222222222,2.4555555555555553,3.362222222222222,2.55,3.362222222222222,2.417777777777778,6.800000000000001 +3.4116666666666666,2.4916666666666663,3.4116666666666666,2.5875,3.4116666666666666,2.453333333333333,6.9 +3.4611111111111112,2.5277777777777777,3.4611111111111112,2.625,3.4611111111111112,2.488888888888889,7.0 +3.5105555555555554,2.5638888888888887,3.5105555555555554,2.6625,3.5105555555555554,2.5244444444444443,7.1000000000000005 +3.56,2.5999999999999996,3.56,2.6999999999999997,3.56,2.56,7.2 +3.6094444444444442,2.636111111111111,3.6094444444444442,2.7375,3.6094444444444442,2.5955555555555554,7.300000000000001 +3.658888888888889,2.672222222222222,3.658888888888889,2.775,3.658888888888889,2.631111111111111,7.4 +3.7083333333333335,2.708333333333333,3.7083333333333335,2.8125,3.7083333333333335,2.6666666666666665,7.5 +3.7577777777777777,2.744444444444444,3.7577777777777777,2.85,3.7577777777777777,2.7022222222222223,7.6000000000000005 +3.8072222222222223,2.7805555555555554,3.8072222222222223,2.8874999999999997,3.8072222222222223,2.7377777777777776,7.7 +3.8566666666666665,2.8166666666666664,3.8566666666666665,2.925,3.8566666666666665,2.7733333333333334,7.800000000000001 +3.906111111111111,2.8527777777777774,3.906111111111111,2.9625,3.906111111111111,2.8088888888888888,7.9 +3.9555555555555557,2.8888888888888884,3.9555555555555557,3.0,3.9555555555555557,2.8444444444444446,8.0 +4.005,2.925,4.005,3.0375,4.005,2.88,8.1 +4.054444444444444,2.961111111111111,4.054444444444444,3.0749999999999997,4.054444444444444,2.9155555555555557,8.200000000000001 +4.103888888888889,2.997222222222222,4.103888888888889,3.1125,4.103888888888889,2.951111111111111,8.3 +4.153333333333333,3.033333333333333,4.153333333333333,3.15,4.153333333333333,2.986666666666667,8.4 +4.2027777777777775,3.069444444444444,4.2027777777777775,3.1875,4.2027777777777775,3.022222222222222,8.5 +4.252222222222223,3.105555555555555,4.252222222222223,3.225,4.252222222222223,3.057777777777778,8.6 +4.301666666666667,3.141666666666666,4.301666666666667,3.2624999999999997,4.301666666666667,3.0933333333333333,8.700000000000001 +4.351111111111111,3.1777777777777776,4.351111111111111,3.3,4.351111111111111,3.128888888888889,8.8 +4.400555555555555,3.2138888888888886,4.400555555555555,3.3375,4.400555555555555,3.1644444444444444,8.9 +4.45,3.2499999999999996,4.45,3.375,4.45,3.2,9.0 +4.499444444444444,3.286111111111111,4.499444444444444,3.4125,4.499444444444444,3.2355555555555555,9.1 +4.5488888888888885,3.322222222222222,4.5488888888888885,3.4499999999999997,4.5488888888888885,3.2711111111111113,9.200000000000001 +4.598333333333334,3.358333333333333,4.598333333333334,3.4875,4.598333333333334,3.3066666666666666,9.3 +4.647777777777778,3.394444444444444,4.647777777777778,3.525,4.647777777777778,3.3422222222222224,9.4 +4.697222222222222,3.4305555555555554,4.697222222222222,3.5625,4.697222222222222,3.3777777777777778,9.5 +4.746666666666666,3.4666666666666663,4.746666666666666,3.5999999999999996,4.746666666666666,3.413333333333333,9.600000000000001 +4.796111111111111,3.5027777777777773,4.796111111111111,3.6374999999999997,4.796111111111111,3.448888888888889,9.700000000000001 +4.845555555555555,3.5388888888888888,4.845555555555555,3.675,4.845555555555555,3.4844444444444442,9.8 +4.895,3.5749999999999997,4.895,3.7125,4.895,3.52,9.9 +4.944444444444445,3.6111111111111107,4.944444444444445,3.75,4.944444444444445,3.5555555555555554,10.0 +4.993888888888889,3.6472222222222217,4.993888888888889,3.7874999999999996,4.993888888888889,3.591111111111111,10.100000000000001 +5.043333333333333,3.683333333333333,5.043333333333333,3.8249999999999997,5.043333333333333,3.6266666666666665,10.200000000000001 +5.092777777777778,3.719444444444444,5.092777777777778,3.8625,5.092777777777778,3.6622222222222223,10.3 +5.142222222222222,3.755555555555555,5.142222222222222,3.9,5.142222222222222,3.6977777777777776,10.4 +5.191666666666666,3.7916666666666665,5.191666666666666,3.9375,5.191666666666666,3.7333333333333334,10.5 +5.241111111111111,3.8277777777777775,5.241111111111111,3.9749999999999996,5.241111111111111,3.7688888888888887,10.600000000000001 +5.290555555555556,3.8638888888888885,5.290555555555556,4.0125,5.290555555555556,3.8044444444444445,10.700000000000001 +5.34,3.8999999999999995,5.34,4.05,5.34,3.84,10.8 +5.389444444444444,3.936111111111111,5.389444444444444,4.0874999999999995,5.389444444444444,3.8755555555555556,10.9 +5.438888888888889,3.972222222222222,5.438888888888889,4.125,5.438888888888889,3.911111111111111,11.0 +5.488333333333333,4.008333333333333,5.488333333333333,4.1625,5.488333333333333,3.9466666666666668,11.100000000000001 +5.5377777777777775,4.044444444444444,5.5377777777777775,4.2,5.5377777777777775,3.982222222222222,11.200000000000001 +5.5872222222222225,4.080555555555555,5.5872222222222225,4.2375,5.5872222222222225,4.017777777777778,11.3 +5.636666666666667,4.116666666666666,5.636666666666667,4.2749999999999995,5.636666666666667,4.053333333333334,11.4 +5.686111111111111,4.152777777777778,5.686111111111111,4.3125,5.686111111111111,4.088888888888889,11.5 +5.735555555555555,4.188888888888888,5.735555555555555,4.35,5.735555555555555,4.124444444444444,11.600000000000001 +5.785,4.225,5.785,4.3875,5.785,4.16,11.700000000000001 +5.834444444444444,4.261111111111111,5.834444444444444,4.425,5.834444444444444,4.195555555555556,11.8 +5.8838888888888885,4.297222222222222,5.8838888888888885,4.4624999999999995,5.8838888888888885,4.231111111111111,11.9 +5.933333333333334,4.333333333333333,5.933333333333334,4.5,5.933333333333334,4.266666666666667,12.0 +5.982777777777778,4.3694444444444445,5.982777777777778,4.5375,5.982777777777778,4.302222222222222,12.100000000000001 +6.032222222222222,4.405555555555555,6.032222222222222,4.575,6.032222222222222,4.337777777777778,12.200000000000001 +6.081666666666667,4.441666666666666,6.081666666666667,4.6125,6.081666666666667,4.373333333333333,12.3 +6.131111111111111,4.477777777777777,6.131111111111111,4.6499999999999995,6.131111111111111,4.408888888888889,12.4 +6.180555555555555,4.513888888888888,6.180555555555555,4.6875,6.180555555555555,4.444444444444445,12.5 +6.2299999999999995,4.55,6.2299999999999995,4.725,6.2299999999999995,4.48,12.600000000000001 +6.279444444444445,4.58611111111111,6.279444444444445,4.7625,6.279444444444445,4.515555555555555,12.700000000000001 +6.328888888888889,4.622222222222222,6.328888888888889,4.8,6.328888888888889,4.551111111111111,12.8 +6.378333333333333,4.658333333333333,6.378333333333333,4.8374999999999995,6.378333333333333,4.586666666666667,12.9 +6.427777777777778,4.694444444444444,6.427777777777778,4.875,6.427777777777778,4.622222222222222,13.0 +6.477222222222222,4.730555555555555,6.477222222222222,4.9125,6.477222222222222,4.657777777777778,13.100000000000001 +6.526666666666666,4.766666666666667,6.526666666666666,4.95,6.526666666666666,4.693333333333333,13.200000000000001 +6.576111111111111,4.802777777777777,6.576111111111111,4.9875,6.576111111111111,4.728888888888889,13.3 +6.625555555555556,4.838888888888889,6.625555555555556,5.0249999999999995,6.625555555555556,4.764444444444444,13.4 +6.675,4.874999999999999,6.675,5.0625,6.675,4.8,13.5 +6.724444444444444,4.9111111111111105,6.724444444444444,5.1,6.724444444444444,4.835555555555556,13.600000000000001 +6.773888888888889,4.947222222222222,6.773888888888889,5.1375,6.773888888888889,4.871111111111111,13.700000000000001 +6.823333333333333,4.9833333333333325,6.823333333333333,5.175,6.823333333333333,4.906666666666666,13.8 +6.872777777777777,5.019444444444444,6.872777777777777,5.2124999999999995,6.872777777777777,4.942222222222222,13.9 +6.9222222222222225,5.055555555555555,6.9222222222222225,5.25,6.9222222222222225,4.977777777777778,14.0 +6.971666666666667,5.091666666666666,6.971666666666667,5.2875,6.971666666666667,5.013333333333334,14.100000000000001 +7.021111111111111,5.127777777777777,7.021111111111111,5.325,7.021111111111111,5.0488888888888885,14.200000000000001 +7.070555555555555,5.163888888888889,7.070555555555555,5.3625,7.070555555555555,5.084444444444444,14.3 +7.12,5.199999999999999,7.12,5.3999999999999995,7.12,5.12,14.4 +7.169444444444444,5.236111111111111,7.169444444444444,5.4375,7.169444444444444,5.155555555555556,14.5 +7.2188888888888885,5.272222222222222,7.2188888888888885,5.475,7.2188888888888885,5.191111111111111,14.600000000000001 +7.2683333333333335,5.308333333333333,7.2683333333333335,5.5125,7.2683333333333335,5.226666666666667,14.700000000000001 +7.317777777777778,5.344444444444444,7.317777777777778,5.55,7.317777777777778,5.262222222222222,14.8 +7.367222222222222,5.380555555555555,7.367222222222222,5.5874999999999995,7.367222222222222,5.297777777777778,14.9 +7.416666666666667,5.416666666666666,7.416666666666667,5.625,7.416666666666667,5.333333333333333,15.0 +7.466111111111111,5.4527777777777775,7.466111111111111,5.6625,7.466111111111111,5.368888888888889,15.100000000000001 +7.515555555555555,5.488888888888888,7.515555555555555,5.7,7.515555555555555,5.404444444444445,15.200000000000001 +7.5649999999999995,5.5249999999999995,7.5649999999999995,5.7375,7.5649999999999995,5.44,15.3 +7.614444444444445,5.561111111111111,7.614444444444445,5.7749999999999995,7.614444444444445,5.475555555555555,15.4 +7.663888888888889,5.597222222222221,7.663888888888889,5.8125,7.663888888888889,5.511111111111111,15.5 +7.713333333333333,5.633333333333333,7.713333333333333,5.85,7.713333333333333,5.546666666666667,15.600000000000001 +7.762777777777778,5.669444444444444,7.762777777777778,5.8875,7.762777777777778,5.582222222222223,15.700000000000001 +7.812222222222222,5.705555555555555,7.812222222222222,5.925,7.812222222222222,5.6177777777777775,15.8 +7.861666666666666,5.741666666666666,7.861666666666666,5.9624999999999995,7.861666666666666,5.653333333333333,15.9 +7.911111111111111,5.777777777777777,7.911111111111111,6.0,7.911111111111111,5.688888888888889,16.0 +7.960555555555556,5.813888888888888,7.960555555555556,6.0375,7.960555555555556,5.724444444444444,16.1 +8.01,5.85,8.01,6.075,8.01,5.76,16.2 +8.059444444444445,5.88611111111111,8.059444444444445,6.1125,8.059444444444445,5.795555555555556,16.3 +8.108888888888888,5.922222222222222,8.108888888888888,6.1499999999999995,8.108888888888888,5.831111111111111,16.400000000000002 +8.158333333333333,5.958333333333333,8.158333333333333,6.1875,8.158333333333333,5.866666666666666,16.5 +8.207777777777778,5.994444444444444,8.207777777777778,6.225,8.207777777777778,5.902222222222222,16.6 +8.257222222222222,6.030555555555555,8.257222222222222,6.2625,8.257222222222222,5.937777777777778,16.7 +8.306666666666667,6.066666666666666,8.306666666666667,6.3,8.306666666666667,5.973333333333334,16.8 +8.356111111111112,6.102777777777777,8.356111111111112,6.3374999999999995,8.356111111111112,6.0088888888888885,16.900000000000002 +8.405555555555555,6.138888888888888,8.405555555555555,6.375,8.405555555555555,6.044444444444444,17.0 +8.455,6.175,8.455,6.4125,8.455,6.08,17.1 +8.504444444444445,6.21111111111111,8.504444444444445,6.45,8.504444444444445,6.115555555555556,17.2 +8.553888888888888,6.247222222222222,8.553888888888888,6.4875,8.553888888888888,6.151111111111111,17.3 +8.603333333333333,6.283333333333332,8.603333333333333,6.5249999999999995,8.603333333333333,6.1866666666666665,17.400000000000002 +8.652777777777777,6.319444444444444,8.652777777777777,6.5625,8.652777777777777,6.222222222222222,17.5 +8.702222222222222,6.355555555555555,8.702222222222222,6.6,8.702222222222222,6.257777777777778,17.6 +8.751666666666667,6.391666666666666,8.751666666666667,6.6375,8.751666666666667,6.293333333333333,17.7 +8.80111111111111,6.427777777777777,8.80111111111111,6.675,8.80111111111111,6.328888888888889,17.8 +8.850555555555555,6.463888888888889,8.850555555555555,6.7124999999999995,8.850555555555555,6.364444444444445,17.900000000000002 +8.9,6.499999999999999,8.9,6.75,8.9,6.4,18.0 +8.949444444444444,6.5361111111111105,8.949444444444444,6.7875,8.949444444444444,6.435555555555555,18.1 +8.998888888888889,6.572222222222222,8.998888888888889,6.825,8.998888888888889,6.471111111111111,18.2 +9.048333333333334,6.6083333333333325,9.048333333333334,6.8625,9.048333333333334,6.506666666666667,18.3 +9.097777777777777,6.644444444444444,9.097777777777777,6.8999999999999995,9.097777777777777,6.542222222222223,18.400000000000002 +9.147222222222222,6.680555555555555,9.147222222222222,6.9375,9.147222222222222,6.5777777777777775,18.5 +9.196666666666667,6.716666666666666,9.196666666666667,6.975,9.196666666666667,6.613333333333333,18.6 +9.24611111111111,6.752777777777777,9.24611111111111,7.0125,9.24611111111111,6.648888888888889,18.7 +9.295555555555556,6.788888888888888,9.295555555555556,7.05,9.295555555555556,6.684444444444445,18.8 +9.345,6.824999999999999,9.345,7.0874999999999995,9.345,6.72,18.900000000000002 +9.394444444444444,6.861111111111111,9.394444444444444,7.125,9.394444444444444,6.7555555555555555,19.0 +9.443888888888889,6.897222222222221,9.443888888888889,7.1625,9.443888888888889,6.791111111111111,19.1 +9.493333333333332,6.933333333333333,9.493333333333332,7.199999999999999,9.493333333333332,6.826666666666666,19.200000000000003 +9.542777777777777,6.969444444444444,9.542777777777777,7.2375,9.542777777777777,6.862222222222222,19.3 +9.592222222222222,7.005555555555555,9.592222222222222,7.2749999999999995,9.592222222222222,6.897777777777778,19.400000000000002 +9.641666666666666,7.041666666666666,9.641666666666666,7.3125,9.641666666666666,6.933333333333334,19.5 +9.69111111111111,7.0777777777777775,9.69111111111111,7.35,9.69111111111111,6.9688888888888885,19.6 +9.740555555555556,7.113888888888888,9.740555555555556,7.387499999999999,9.740555555555556,7.004444444444444,19.700000000000003 +9.79,7.1499999999999995,9.79,7.425,9.79,7.04,19.8 +9.839444444444444,7.18611111111111,9.839444444444444,7.4624999999999995,9.839444444444444,7.075555555555556,19.900000000000002 +9.88888888888889,7.222222222222221,9.88888888888889,7.5,9.88888888888889,7.111111111111111,20.0 +9.938333333333333,7.258333333333333,9.938333333333333,7.5375,9.938333333333333,7.1466666666666665,20.1 +9.987777777777778,7.294444444444443,9.987777777777778,7.574999999999999,9.987777777777778,7.182222222222222,20.200000000000003 +10.037222222222223,7.330555555555555,10.037222222222223,7.6125,10.037222222222223,7.217777777777778,20.3 +10.086666666666666,7.366666666666666,10.086666666666666,7.6499999999999995,10.086666666666666,7.253333333333333,20.400000000000002 +10.136111111111111,7.402777777777777,10.136111111111111,7.6875,10.136111111111111,7.288888888888889,20.5 +10.185555555555556,7.438888888888888,10.185555555555556,7.725,10.185555555555556,7.3244444444444445,20.6 +10.235,7.475,10.235,7.762499999999999,10.235,7.36,20.700000000000003 +10.284444444444444,7.51111111111111,10.284444444444444,7.8,10.284444444444444,7.395555555555555,20.8 +10.33388888888889,7.547222222222222,10.33388888888889,7.8374999999999995,10.33388888888889,7.431111111111111,20.900000000000002 +10.383333333333333,7.583333333333333,10.383333333333333,7.875,10.383333333333333,7.466666666666667,21.0 +10.432777777777778,7.619444444444444,10.432777777777778,7.9125,10.432777777777778,7.502222222222223,21.1 +10.482222222222221,7.655555555555555,10.482222222222221,7.949999999999999,10.482222222222221,7.5377777777777775,21.200000000000003 +10.531666666666666,7.6916666666666655,10.531666666666666,7.9875,10.531666666666666,7.573333333333333,21.3 +10.581111111111111,7.727777777777777,10.581111111111111,8.025,10.581111111111111,7.608888888888889,21.400000000000002 +10.630555555555555,7.763888888888888,10.630555555555555,8.0625,10.630555555555555,7.644444444444445,21.5 +10.68,7.799999999999999,10.68,8.1,10.68,7.68,21.6 +10.729444444444445,7.83611111111111,10.729444444444445,8.1375,10.729444444444445,7.7155555555555555,21.700000000000003 +10.778888888888888,7.872222222222222,10.778888888888888,8.174999999999999,10.778888888888888,7.751111111111111,21.8 +10.828333333333333,7.908333333333332,10.828333333333333,8.2125,10.828333333333333,7.786666666666667,21.900000000000002 +10.877777777777778,7.944444444444444,10.877777777777778,8.25,10.877777777777778,7.822222222222222,22.0 +10.927222222222222,7.980555555555555,10.927222222222222,8.2875,10.927222222222222,7.857777777777778,22.1 +10.976666666666667,8.016666666666666,10.976666666666667,8.325,10.976666666666667,7.8933333333333335,22.200000000000003 +11.026111111111112,8.052777777777777,11.026111111111112,8.362499999999999,11.026111111111112,7.928888888888889,22.3 +11.075555555555555,8.088888888888889,11.075555555555555,8.4,11.075555555555555,7.964444444444444,22.400000000000002 +11.125,8.125,11.125,8.4375,11.125,8.0,22.5 +11.174444444444445,8.16111111111111,11.174444444444445,8.475,11.174444444444445,8.035555555555556,22.6 +11.223888888888888,8.197222222222221,11.223888888888888,8.5125,11.223888888888888,8.071111111111112,22.700000000000003 +11.273333333333333,8.233333333333333,11.273333333333333,8.549999999999999,11.273333333333333,8.106666666666667,22.8 +11.322777777777777,8.269444444444444,11.322777777777777,8.5875,11.322777777777777,8.142222222222221,22.900000000000002 +11.372222222222222,8.305555555555555,11.372222222222222,8.625,11.372222222222222,8.177777777777777,23.0 +11.421666666666667,8.341666666666665,11.421666666666667,8.6625,11.421666666666667,8.213333333333333,23.1 +11.47111111111111,8.377777777777776,11.47111111111111,8.7,11.47111111111111,8.248888888888889,23.200000000000003 +11.520555555555555,8.413888888888888,11.520555555555555,8.737499999999999,11.520555555555555,8.284444444444444,23.3 +11.57,8.45,11.57,8.775,11.57,8.32,23.400000000000002 +11.619444444444444,8.48611111111111,11.619444444444444,8.8125,11.619444444444444,8.355555555555556,23.5 +11.668888888888889,8.522222222222222,11.668888888888889,8.85,11.668888888888889,8.391111111111112,23.6 +11.718333333333334,8.558333333333332,11.718333333333334,8.8875,11.718333333333334,8.426666666666666,23.700000000000003 +11.767777777777777,8.594444444444443,11.767777777777777,8.924999999999999,11.767777777777777,8.462222222222222,23.8 +11.817222222222222,8.630555555555555,11.817222222222222,8.9625,11.817222222222222,8.497777777777777,23.900000000000002 +11.866666666666667,8.666666666666666,11.866666666666667,9.0,11.866666666666667,8.533333333333333,24.0 +11.91611111111111,8.702777777777778,11.91611111111111,9.0375,11.91611111111111,8.568888888888889,24.1 +11.965555555555556,8.738888888888889,11.965555555555556,9.075,11.965555555555556,8.604444444444445,24.200000000000003 +12.015,8.774999999999999,12.015,9.112499999999999,12.015,8.64,24.3 +12.064444444444444,8.81111111111111,12.064444444444444,9.15,12.064444444444444,8.675555555555556,24.400000000000002 +12.113888888888889,8.847222222222221,12.113888888888889,9.1875,12.113888888888889,8.71111111111111,24.5 +12.163333333333334,8.883333333333333,12.163333333333334,9.225,12.163333333333334,8.746666666666666,24.6 +12.212777777777777,8.919444444444444,12.212777777777777,9.2625,12.212777777777777,8.782222222222222,24.700000000000003 +12.262222222222222,8.955555555555554,12.262222222222222,9.299999999999999,12.262222222222222,8.817777777777778,24.8 +12.311666666666666,8.991666666666665,12.311666666666666,9.3375,12.311666666666666,8.853333333333333,24.900000000000002 +12.36111111111111,9.027777777777777,12.36111111111111,9.375,12.36111111111111,8.88888888888889,25.0 +12.410555555555556,9.063888888888888,12.410555555555556,9.4125,12.410555555555556,8.924444444444445,25.1 +12.459999999999999,9.1,12.459999999999999,9.45,12.459999999999999,8.96,25.200000000000003 +12.509444444444444,9.136111111111111,12.509444444444444,9.487499999999999,12.509444444444444,8.995555555555555,25.3 +12.55888888888889,9.17222222222222,12.55888888888889,9.525,12.55888888888889,9.03111111111111,25.400000000000002 +12.608333333333333,9.208333333333332,12.608333333333333,9.5625,12.608333333333333,9.066666666666666,25.5 +12.657777777777778,9.244444444444444,12.657777777777778,9.6,12.657777777777778,9.102222222222222,25.6 +12.707222222222223,9.280555555555555,12.707222222222223,9.6375,12.707222222222223,9.137777777777778,25.700000000000003 +12.756666666666666,9.316666666666666,12.756666666666666,9.674999999999999,12.756666666666666,9.173333333333334,25.8 +12.806111111111111,9.352777777777776,12.806111111111111,9.7125,12.806111111111111,9.20888888888889,25.900000000000002 +12.855555555555556,9.388888888888888,12.855555555555556,9.75,12.855555555555556,9.244444444444444,26.0 +12.905,9.424999999999999,12.905,9.7875,12.905,9.28,26.1 +12.954444444444444,9.46111111111111,12.954444444444444,9.825,12.954444444444444,9.315555555555555,26.200000000000003 +13.00388888888889,9.497222222222222,13.00388888888889,9.862499999999999,13.00388888888889,9.351111111111111,26.3 +13.053333333333333,9.533333333333333,13.053333333333333,9.9,13.053333333333333,9.386666666666667,26.400000000000002 +13.102777777777778,9.569444444444443,13.102777777777778,9.9375,13.102777777777778,9.422222222222222,26.5 +13.152222222222221,9.605555555555554,13.152222222222221,9.975,13.152222222222221,9.457777777777778,26.6 +13.201666666666666,9.641666666666666,13.201666666666666,10.0125,13.201666666666666,9.493333333333334,26.700000000000003 +13.251111111111111,9.677777777777777,13.251111111111111,10.049999999999999,13.251111111111111,9.528888888888888,26.8 +13.300555555555555,9.713888888888889,13.300555555555555,10.0875,13.300555555555555,9.564444444444444,26.900000000000002 +13.35,9.749999999999998,13.35,10.125,13.35,9.6,27.0 +13.399444444444445,9.78611111111111,13.399444444444445,10.1625,13.399444444444445,9.635555555555555,27.1 +13.448888888888888,9.822222222222221,13.448888888888888,10.2,13.448888888888888,9.671111111111111,27.200000000000003 +13.498333333333333,9.858333333333333,13.498333333333333,10.237499999999999,13.498333333333333,9.706666666666667,27.3 +13.547777777777778,9.894444444444444,13.547777777777778,10.275,13.547777777777778,9.742222222222223,27.400000000000002 +13.597222222222221,9.930555555555555,13.597222222222221,10.3125,13.597222222222221,9.777777777777779,27.5 +13.646666666666667,9.966666666666665,13.646666666666667,10.35,13.646666666666667,9.813333333333333,27.6 +13.696111111111112,10.002777777777776,13.696111111111112,10.3875,13.696111111111112,9.848888888888888,27.700000000000003 +13.745555555555555,10.038888888888888,13.745555555555555,10.424999999999999,13.745555555555555,9.884444444444444,27.8 +13.795,10.075,13.795,10.4625,13.795,9.92,27.900000000000002 +13.844444444444445,10.11111111111111,13.844444444444445,10.5,13.844444444444445,9.955555555555556,28.0 +13.893888888888888,10.147222222222222,13.893888888888888,10.5375,13.893888888888888,9.991111111111111,28.1 +13.943333333333333,10.183333333333332,13.943333333333333,10.575,13.943333333333333,10.026666666666667,28.200000000000003 +13.992777777777778,10.219444444444443,13.992777777777778,10.612499999999999,13.992777777777778,10.062222222222223,28.3 +14.042222222222222,10.255555555555555,14.042222222222222,10.65,14.042222222222222,10.097777777777777,28.400000000000002 +14.091666666666667,10.291666666666666,14.091666666666667,10.6875,14.091666666666667,10.133333333333333,28.5 +14.14111111111111,10.327777777777778,14.14111111111111,10.725,14.14111111111111,10.168888888888889,28.6 +14.190555555555555,10.363888888888887,14.190555555555555,10.7625,14.190555555555555,10.204444444444444,28.700000000000003 +14.24,10.399999999999999,14.24,10.799999999999999,14.24,10.24,28.8 +14.289444444444444,10.43611111111111,14.289444444444444,10.8375,14.289444444444444,10.275555555555556,28.900000000000002 +14.338888888888889,10.472222222222221,14.338888888888889,10.875,14.338888888888889,10.311111111111112,29.0 +14.388333333333334,10.508333333333333,14.388333333333334,10.9125,14.388333333333334,10.346666666666666,29.1 +14.437777777777777,10.544444444444444,14.437777777777777,10.95,14.437777777777777,10.382222222222222,29.200000000000003 +14.487222222222222,10.580555555555554,14.487222222222222,10.987499999999999,14.487222222222222,10.417777777777777,29.3 +14.536666666666667,10.616666666666665,14.536666666666667,11.025,14.536666666666667,10.453333333333333,29.400000000000002 +14.58611111111111,10.652777777777777,14.58611111111111,11.0625,14.58611111111111,10.488888888888889,29.5 +14.635555555555555,10.688888888888888,14.635555555555555,11.1,14.635555555555555,10.524444444444445,29.6 +14.685,10.725,14.685,11.1375,14.685,10.56,29.700000000000003 +14.734444444444444,10.76111111111111,14.734444444444444,11.174999999999999,14.734444444444444,10.595555555555556,29.8 +14.783888888888889,10.79722222222222,14.783888888888889,11.2125,14.783888888888889,10.63111111111111,29.900000000000002 +14.833333333333334,10.833333333333332,14.833333333333334,11.25,14.833333333333334,10.666666666666666,30.0 +14.882777777777777,10.869444444444444,14.882777777777777,11.2875,14.882777777777777,10.702222222222222,30.1 +14.932222222222222,10.905555555555555,14.932222222222222,11.325,14.932222222222222,10.737777777777778,30.200000000000003 +14.981666666666666,10.941666666666666,14.981666666666666,11.362499999999999,14.981666666666666,10.773333333333333,30.3 +15.03111111111111,10.977777777777776,15.03111111111111,11.4,15.03111111111111,10.80888888888889,30.400000000000002 +15.080555555555556,11.013888888888888,15.080555555555556,11.4375,15.080555555555556,10.844444444444445,30.5 +15.129999999999999,11.049999999999999,15.129999999999999,11.475,15.129999999999999,10.88,30.6 +15.179444444444444,11.08611111111111,15.179444444444444,11.5125,15.179444444444444,10.915555555555555,30.700000000000003 +15.22888888888889,11.122222222222222,15.22888888888889,11.549999999999999,15.22888888888889,10.95111111111111,30.8 +15.278333333333332,11.158333333333331,15.278333333333332,11.5875,15.278333333333332,10.986666666666666,30.900000000000002 +15.327777777777778,11.194444444444443,15.327777777777778,11.625,15.327777777777778,11.022222222222222,31.0 +15.377222222222223,11.230555555555554,15.377222222222223,11.6625,15.377222222222223,11.057777777777778,31.1 +15.426666666666666,11.266666666666666,15.426666666666666,11.7,15.426666666666666,11.093333333333334,31.200000000000003 +15.476111111111111,11.302777777777777,15.476111111111111,11.737499999999999,15.476111111111111,11.12888888888889,31.3 +15.525555555555556,11.338888888888889,15.525555555555556,11.775,15.525555555555556,11.164444444444445,31.400000000000002 +15.575,11.374999999999998,15.575,11.8125,15.575,11.2,31.5 +15.624444444444444,11.41111111111111,15.624444444444444,11.85,15.624444444444444,11.235555555555555,31.6 +15.67388888888889,11.447222222222221,15.67388888888889,11.8875,15.67388888888889,11.27111111111111,31.700000000000003 +15.723333333333333,11.483333333333333,15.723333333333333,11.924999999999999,15.723333333333333,11.306666666666667,31.8 +15.772777777777778,11.519444444444444,15.772777777777778,11.9625,15.772777777777778,11.342222222222222,31.900000000000002 +15.822222222222223,11.555555555555554,15.822222222222223,12.0,15.822222222222223,11.377777777777778,32.0 +15.871666666666666,11.591666666666665,15.871666666666666,12.0375,15.871666666666666,11.413333333333334,32.1 +15.921111111111111,11.627777777777776,15.921111111111111,12.075,15.921111111111111,11.448888888888888,32.2 +15.970555555555555,11.663888888888888,15.970555555555555,12.112499999999999,15.970555555555555,11.484444444444444,32.300000000000004 +16.02,11.7,16.02,12.15,16.02,11.52,32.4 +16.069444444444443,11.73611111111111,16.069444444444443,12.1875,16.069444444444443,11.555555555555555,32.5 +16.11888888888889,11.77222222222222,16.11888888888889,12.225,16.11888888888889,11.591111111111111,32.6 +16.168333333333333,11.808333333333332,16.168333333333333,12.2625,16.168333333333333,11.626666666666667,32.7 +16.217777777777776,11.844444444444443,16.217777777777776,12.299999999999999,16.217777777777776,11.662222222222223,32.800000000000004 +16.267222222222223,11.880555555555555,16.267222222222223,12.3375,16.267222222222223,11.697777777777778,32.9 +16.316666666666666,11.916666666666666,16.316666666666666,12.375,16.316666666666666,11.733333333333333,33.0 +16.36611111111111,11.952777777777778,16.36611111111111,12.4125,16.36611111111111,11.768888888888888,33.1 +16.415555555555557,11.988888888888887,16.415555555555557,12.45,16.415555555555557,11.804444444444444,33.2 +16.465,12.024999999999999,16.465,12.487499999999999,16.465,11.84,33.300000000000004 +16.514444444444443,12.06111111111111,16.514444444444443,12.525,16.514444444444443,11.875555555555556,33.4 +16.56388888888889,12.097222222222221,16.56388888888889,12.5625,16.56388888888889,11.911111111111111,33.5 +16.613333333333333,12.133333333333333,16.613333333333333,12.6,16.613333333333333,11.946666666666667,33.6 +16.662777777777777,12.169444444444443,16.662777777777777,12.6375,16.662777777777777,11.982222222222223,33.7 +16.712222222222223,12.205555555555554,16.712222222222223,12.674999999999999,16.712222222222223,12.017777777777777,33.800000000000004 +16.761666666666667,12.241666666666665,16.761666666666667,12.7125,16.761666666666667,12.053333333333333,33.9 +16.81111111111111,12.277777777777777,16.81111111111111,12.75,16.81111111111111,12.088888888888889,34.0 +16.860555555555557,12.313888888888888,16.860555555555557,12.7875,16.860555555555557,12.124444444444444,34.1 +16.91,12.35,16.91,12.825,16.91,12.16,34.2 +16.959444444444443,12.38611111111111,16.959444444444443,12.862499999999999,16.959444444444443,12.195555555555556,34.300000000000004 +17.00888888888889,12.42222222222222,17.00888888888889,12.9,17.00888888888889,12.231111111111112,34.4 +17.058333333333334,12.458333333333332,17.058333333333334,12.9375,17.058333333333334,12.266666666666667,34.5 +17.107777777777777,12.494444444444444,17.107777777777777,12.975,17.107777777777777,12.302222222222222,34.6 +17.157222222222224,12.530555555555555,17.157222222222224,13.0125,17.157222222222224,12.337777777777777,34.7 +17.206666666666667,12.566666666666665,17.206666666666667,13.049999999999999,17.206666666666667,12.373333333333333,34.800000000000004 +17.25611111111111,12.602777777777776,17.25611111111111,13.0875,17.25611111111111,12.408888888888889,34.9 +17.305555555555554,12.638888888888888,17.305555555555554,13.125,17.305555555555554,12.444444444444445,35.0 +17.355,12.674999999999999,17.355,13.1625,17.355,12.48,35.1 +17.404444444444444,12.71111111111111,17.404444444444444,13.2,17.404444444444444,12.515555555555556,35.2 +17.453888888888887,12.747222222222222,17.453888888888887,13.237499999999999,17.453888888888887,12.55111111111111,35.300000000000004 +17.503333333333334,12.783333333333331,17.503333333333334,13.275,17.503333333333334,12.586666666666666,35.4 +17.552777777777777,12.819444444444443,17.552777777777777,13.3125,17.552777777777777,12.622222222222222,35.5 +17.60222222222222,12.855555555555554,17.60222222222222,13.35,17.60222222222222,12.657777777777778,35.6 +17.651666666666667,12.891666666666666,17.651666666666667,13.3875,17.651666666666667,12.693333333333333,35.7 +17.70111111111111,12.927777777777777,17.70111111111111,13.424999999999999,17.70111111111111,12.72888888888889,35.800000000000004 +17.750555555555554,12.963888888888887,17.750555555555554,13.4625,17.750555555555554,12.764444444444445,35.9 +17.8,12.999999999999998,17.8,13.5,17.8,12.8,36.0 +17.849444444444444,13.03611111111111,17.849444444444444,13.5375,17.849444444444444,12.835555555555555,36.1 +17.898888888888887,13.072222222222221,17.898888888888887,13.575,17.898888888888887,12.87111111111111,36.2 +17.948333333333334,13.108333333333333,17.948333333333334,13.612499999999999,17.948333333333334,12.906666666666666,36.300000000000004 +17.997777777777777,13.144444444444444,17.997777777777777,13.65,17.997777777777777,12.942222222222222,36.4 +18.04722222222222,13.180555555555554,18.04722222222222,13.6875,18.04722222222222,12.977777777777778,36.5 +18.096666666666668,13.216666666666665,18.096666666666668,13.725,18.096666666666668,13.013333333333334,36.6 +18.14611111111111,13.252777777777776,18.14611111111111,13.7625,18.14611111111111,13.04888888888889,36.7 +18.195555555555554,13.288888888888888,18.195555555555554,13.799999999999999,18.195555555555554,13.084444444444445,36.800000000000004 +18.245,13.325,18.245,13.8375,18.245,13.12,36.9 +18.294444444444444,13.36111111111111,18.294444444444444,13.875,18.294444444444444,13.155555555555555,37.0 +18.343888888888888,13.39722222222222,18.343888888888888,13.9125,18.343888888888888,13.19111111111111,37.1 +18.393333333333334,13.433333333333332,18.393333333333334,13.95,18.393333333333334,13.226666666666667,37.2 +18.442777777777778,13.469444444444443,18.442777777777778,13.987499999999999,18.442777777777778,13.262222222222222,37.300000000000004 +18.49222222222222,13.505555555555555,18.49222222222222,14.025,18.49222222222222,13.297777777777778,37.4 +18.541666666666668,13.541666666666666,18.541666666666668,14.0625,18.541666666666668,13.333333333333334,37.5 +18.59111111111111,13.577777777777776,18.59111111111111,14.1,18.59111111111111,13.36888888888889,37.6 +18.640555555555554,13.613888888888887,18.640555555555554,14.1375,18.640555555555554,13.404444444444444,37.7 +18.69,13.649999999999999,18.69,14.174999999999999,18.69,13.44,37.800000000000004 +18.739444444444445,13.68611111111111,18.739444444444445,14.2125,18.739444444444445,13.475555555555555,37.9 +18.788888888888888,13.722222222222221,18.788888888888888,14.25,18.788888888888888,13.511111111111111,38.0 +18.838333333333335,13.758333333333333,18.838333333333335,14.2875,18.838333333333335,13.546666666666667,38.1 +18.887777777777778,13.794444444444443,18.887777777777778,14.325,18.887777777777778,13.582222222222223,38.2 +18.93722222222222,13.830555555555554,18.93722222222222,14.362499999999999,18.93722222222222,13.617777777777778,38.300000000000004 +18.986666666666665,13.866666666666665,18.986666666666665,14.399999999999999,18.986666666666665,13.653333333333332,38.400000000000006 +19.03611111111111,13.902777777777777,19.03611111111111,14.4375,19.03611111111111,13.688888888888888,38.5 +19.085555555555555,13.938888888888888,19.085555555555555,14.475,19.085555555555555,13.724444444444444,38.6 +19.134999999999998,13.974999999999998,19.134999999999998,14.5125,19.134999999999998,13.76,38.7 +19.184444444444445,14.01111111111111,19.184444444444445,14.549999999999999,19.184444444444445,13.795555555555556,38.800000000000004 +19.233888888888888,14.04722222222222,19.233888888888888,14.587499999999999,19.233888888888888,13.831111111111111,38.900000000000006 +19.28333333333333,14.083333333333332,19.28333333333333,14.625,19.28333333333333,13.866666666666667,39.0 +19.33277777777778,14.119444444444444,19.33277777777778,14.6625,19.33277777777778,13.902222222222223,39.1 +19.38222222222222,14.155555555555555,19.38222222222222,14.7,19.38222222222222,13.937777777777777,39.2 +19.431666666666665,14.191666666666665,19.431666666666665,14.737499999999999,19.431666666666665,13.973333333333333,39.300000000000004 +19.48111111111111,14.227777777777776,19.48111111111111,14.774999999999999,19.48111111111111,14.008888888888889,39.400000000000006 +19.530555555555555,14.263888888888888,19.530555555555555,14.8125,19.530555555555555,14.044444444444444,39.5 +19.58,14.299999999999999,19.58,14.85,19.58,14.08,39.6 +19.629444444444445,14.33611111111111,19.629444444444445,14.8875,19.629444444444445,14.115555555555556,39.7 +19.67888888888889,14.37222222222222,19.67888888888889,14.924999999999999,19.67888888888889,14.151111111111112,39.800000000000004 +19.72833333333333,14.408333333333331,19.72833333333333,14.962499999999999,19.72833333333333,14.186666666666667,39.900000000000006 +19.77777777777778,14.444444444444443,19.77777777777778,15.0,19.77777777777778,14.222222222222221,40.0 +19.827222222222222,14.480555555555554,19.827222222222222,15.0375,19.827222222222222,14.257777777777777,40.1 +19.876666666666665,14.516666666666666,19.876666666666665,15.075,19.876666666666665,14.293333333333333,40.2 +19.926111111111112,14.552777777777777,19.926111111111112,15.112499999999999,19.926111111111112,14.328888888888889,40.300000000000004 +19.975555555555555,14.588888888888887,19.975555555555555,15.149999999999999,19.975555555555555,14.364444444444445,40.400000000000006 +20.025,14.624999999999998,20.025,15.1875,20.025,14.4,40.5 +20.074444444444445,14.66111111111111,20.074444444444445,15.225,20.074444444444445,14.435555555555556,40.6 +20.12388888888889,14.697222222222221,20.12388888888889,15.2625,20.12388888888889,14.471111111111112,40.7 +20.173333333333332,14.733333333333333,20.173333333333332,15.299999999999999,20.173333333333332,14.506666666666666,40.800000000000004 +20.22277777777778,14.769444444444444,20.22277777777778,15.337499999999999,20.22277777777778,14.542222222222222,40.900000000000006 +20.272222222222222,14.805555555555554,20.272222222222222,15.375,20.272222222222222,14.577777777777778,41.0 +20.321666666666665,14.841666666666665,20.321666666666665,15.4125,20.321666666666665,14.613333333333333,41.1 +20.371111111111112,14.877777777777776,20.371111111111112,15.45,20.371111111111112,14.648888888888889,41.2 +20.420555555555556,14.913888888888888,20.420555555555556,15.487499999999999,20.420555555555556,14.684444444444445,41.300000000000004 +20.47,14.95,20.47,15.524999999999999,20.47,14.72,41.400000000000006 +20.519444444444446,14.986111111111109,20.519444444444446,15.5625,20.519444444444446,14.755555555555556,41.5 +20.56888888888889,15.02222222222222,20.56888888888889,15.6,20.56888888888889,14.79111111111111,41.6 +20.618333333333332,15.058333333333332,20.618333333333332,15.6375,20.618333333333332,14.826666666666666,41.7 +20.66777777777778,15.094444444444443,20.66777777777778,15.674999999999999,20.66777777777778,14.862222222222222,41.800000000000004 +20.717222222222222,15.130555555555555,20.717222222222222,15.712499999999999,20.717222222222222,14.897777777777778,41.900000000000006 +20.766666666666666,15.166666666666666,20.766666666666666,15.75,20.766666666666666,14.933333333333334,42.0 +20.81611111111111,15.202777777777776,20.81611111111111,15.7875,20.81611111111111,14.96888888888889,42.1 +20.865555555555556,15.238888888888887,20.865555555555556,15.825,20.865555555555556,15.004444444444445,42.2 +20.915,15.274999999999999,20.915,15.862499999999999,20.915,15.04,42.300000000000004 +20.964444444444442,15.31111111111111,20.964444444444442,15.899999999999999,20.964444444444442,15.075555555555555,42.400000000000006 +21.01388888888889,15.347222222222221,21.01388888888889,15.9375,21.01388888888889,15.11111111111111,42.5 +21.063333333333333,15.383333333333331,21.063333333333333,15.975,21.063333333333333,15.146666666666667,42.6 +21.112777777777776,15.419444444444443,21.112777777777776,16.0125,21.112777777777776,15.182222222222222,42.7 +21.162222222222223,15.455555555555554,21.162222222222223,16.05,21.162222222222223,15.217777777777778,42.800000000000004 +21.211666666666666,15.491666666666665,21.211666666666666,16.0875,21.211666666666666,15.253333333333334,42.900000000000006 +21.26111111111111,15.527777777777777,21.26111111111111,16.125,21.26111111111111,15.28888888888889,43.0 +21.310555555555556,15.563888888888888,21.310555555555556,16.162499999999998,21.310555555555556,15.324444444444444,43.1 +21.36,15.599999999999998,21.36,16.2,21.36,15.36,43.2 +21.409444444444443,15.63611111111111,21.409444444444443,16.2375,21.409444444444443,15.395555555555555,43.300000000000004 +21.45888888888889,15.67222222222222,21.45888888888889,16.275,21.45888888888889,15.431111111111111,43.400000000000006 +21.508333333333333,15.708333333333332,21.508333333333333,16.3125,21.508333333333333,15.466666666666667,43.5 +21.557777777777776,15.744444444444444,21.557777777777776,16.349999999999998,21.557777777777776,15.502222222222223,43.6 +21.607222222222223,15.780555555555553,21.607222222222223,16.3875,21.607222222222223,15.537777777777778,43.7 +21.656666666666666,15.816666666666665,21.656666666666666,16.425,21.656666666666666,15.573333333333334,43.800000000000004 +21.70611111111111,15.852777777777776,21.70611111111111,16.4625,21.70611111111111,15.608888888888888,43.900000000000006 +21.755555555555556,15.888888888888888,21.755555555555556,16.5,21.755555555555556,15.644444444444444,44.0 +21.805,15.924999999999999,21.805,16.537499999999998,21.805,15.68,44.1 +21.854444444444443,15.96111111111111,21.854444444444443,16.575,21.854444444444443,15.715555555555556,44.2 +21.90388888888889,15.99722222222222,21.90388888888889,16.6125,21.90388888888889,15.751111111111111,44.300000000000004 +21.953333333333333,16.03333333333333,21.953333333333333,16.65,21.953333333333333,15.786666666666667,44.400000000000006 +22.002777777777776,16.069444444444443,22.002777777777776,16.6875,22.002777777777776,15.822222222222223,44.5 +22.052222222222223,16.105555555555554,22.052222222222223,16.724999999999998,22.052222222222223,15.857777777777779,44.6 +22.101666666666667,16.141666666666666,22.101666666666667,16.7625,22.101666666666667,15.893333333333333,44.7 +22.15111111111111,16.177777777777777,22.15111111111111,16.8,22.15111111111111,15.928888888888888,44.800000000000004 +22.200555555555557,16.21388888888889,22.200555555555557,16.8375,22.200555555555557,15.964444444444444,44.900000000000006 +22.25,16.25,22.25,16.875,22.25,16.0,45.0 +22.299444444444443,16.286111111111108,22.299444444444443,16.912499999999998,22.299444444444443,16.035555555555554,45.1 +22.34888888888889,16.32222222222222,22.34888888888889,16.95,22.34888888888889,16.07111111111111,45.2 +22.398333333333333,16.35833333333333,22.398333333333333,16.9875,22.398333333333333,16.106666666666666,45.300000000000004 +22.447777777777777,16.394444444444442,22.447777777777777,17.025,22.447777777777777,16.142222222222223,45.400000000000006 +22.497222222222224,16.430555555555554,22.497222222222224,17.0625,22.497222222222224,16.177777777777777,45.5 +22.546666666666667,16.466666666666665,22.546666666666667,17.099999999999998,22.546666666666667,16.213333333333335,45.6 +22.59611111111111,16.502777777777776,22.59611111111111,17.1375,22.59611111111111,16.24888888888889,45.7 +22.645555555555553,16.538888888888888,22.645555555555553,17.175,22.645555555555553,16.284444444444443,45.800000000000004 +22.695,16.575,22.695,17.2125,22.695,16.32,45.900000000000006 +22.744444444444444,16.61111111111111,22.744444444444444,17.25,22.744444444444444,16.355555555555554,46.0 +22.793888888888887,16.647222222222222,22.793888888888887,17.287499999999998,22.793888888888887,16.391111111111112,46.1 +22.843333333333334,16.68333333333333,22.843333333333334,17.325,22.843333333333334,16.426666666666666,46.2 +22.892777777777777,16.71944444444444,22.892777777777777,17.3625,22.892777777777777,16.462222222222223,46.300000000000004 +22.94222222222222,16.755555555555553,22.94222222222222,17.4,22.94222222222222,16.497777777777777,46.400000000000006 +22.991666666666667,16.791666666666664,22.991666666666667,17.4375,22.991666666666667,16.533333333333335,46.5 +23.04111111111111,16.827777777777776,23.04111111111111,17.474999999999998,23.04111111111111,16.56888888888889,46.6 +23.090555555555554,16.863888888888887,23.090555555555554,17.5125,23.090555555555554,16.604444444444443,46.7 +23.14,16.9,23.14,17.55,23.14,16.64,46.800000000000004 +23.189444444444444,16.93611111111111,23.189444444444444,17.5875,23.189444444444444,16.675555555555555,46.900000000000006 +23.238888888888887,16.97222222222222,23.238888888888887,17.625,23.238888888888887,16.711111111111112,47.0 +23.288333333333334,17.008333333333333,23.288333333333334,17.662499999999998,23.288333333333334,16.746666666666666,47.1 +23.337777777777777,17.044444444444444,23.337777777777777,17.7,23.337777777777777,16.782222222222224,47.2 +23.38722222222222,17.080555555555556,23.38722222222222,17.7375,23.38722222222222,16.817777777777778,47.300000000000004 +23.436666666666667,17.116666666666664,23.436666666666667,17.775,23.436666666666667,16.85333333333333,47.400000000000006 +23.48611111111111,17.152777777777775,23.48611111111111,17.8125,23.48611111111111,16.88888888888889,47.5 +23.535555555555554,17.188888888888886,23.535555555555554,17.849999999999998,23.535555555555554,16.924444444444443,47.6 +23.585,17.224999999999998,23.585,17.8875,23.585,16.96,47.7 +23.634444444444444,17.26111111111111,23.634444444444444,17.925,23.634444444444444,16.995555555555555,47.800000000000004 +23.683888888888887,17.29722222222222,23.683888888888887,17.9625,23.683888888888887,17.031111111111112,47.900000000000006 +23.733333333333334,17.333333333333332,23.733333333333334,18.0,23.733333333333334,17.066666666666666,48.0 +23.782777777777778,17.369444444444444,23.782777777777778,18.037499999999998,23.782777777777778,17.10222222222222,48.1 +23.83222222222222,17.405555555555555,23.83222222222222,18.075,23.83222222222222,17.137777777777778,48.2 +23.881666666666668,17.441666666666666,23.881666666666668,18.1125,23.881666666666668,17.173333333333332,48.300000000000004 +23.93111111111111,17.477777777777778,23.93111111111111,18.15,23.93111111111111,17.20888888888889,48.400000000000006 +23.980555555555554,17.513888888888886,23.980555555555554,18.1875,23.980555555555554,17.244444444444444,48.5 +24.03,17.549999999999997,24.03,18.224999999999998,24.03,17.28,48.6 +24.079444444444444,17.58611111111111,24.079444444444444,18.2625,24.079444444444444,17.315555555555555,48.7 +24.128888888888888,17.62222222222222,24.128888888888888,18.3,24.128888888888888,17.351111111111113,48.800000000000004 +24.178333333333335,17.65833333333333,24.178333333333335,18.3375,24.178333333333335,17.386666666666667,48.900000000000006 +24.227777777777778,17.694444444444443,24.227777777777778,18.375,24.227777777777778,17.42222222222222,49.0 +24.27722222222222,17.730555555555554,24.27722222222222,18.412499999999998,24.27722222222222,17.45777777777778,49.1 +24.326666666666668,17.766666666666666,24.326666666666668,18.45,24.326666666666668,17.493333333333332,49.2 +24.37611111111111,17.802777777777777,24.37611111111111,18.4875,24.37611111111111,17.52888888888889,49.300000000000004 +24.425555555555555,17.83888888888889,24.425555555555555,18.525,24.425555555555555,17.564444444444444,49.400000000000006 +24.474999999999998,17.875,24.474999999999998,18.5625,24.474999999999998,17.6,49.5 +24.524444444444445,17.911111111111108,24.524444444444445,18.599999999999998,24.524444444444445,17.635555555555555,49.6 +24.573888888888888,17.94722222222222,24.573888888888888,18.6375,24.573888888888888,17.67111111111111,49.7 +24.62333333333333,17.98333333333333,24.62333333333333,18.675,24.62333333333333,17.706666666666667,49.800000000000004 +24.672777777777778,18.019444444444442,24.672777777777778,18.7125,24.672777777777778,17.74222222222222,49.900000000000006 +24.72222222222222,18.055555555555554,24.72222222222222,18.75,24.72222222222222,17.77777777777778,50.0 +24.771666666666665,18.091666666666665,24.771666666666665,18.787499999999998,24.771666666666665,17.813333333333333,50.1 +24.82111111111111,18.127777777777776,24.82111111111111,18.825,24.82111111111111,17.84888888888889,50.2 +24.870555555555555,18.163888888888888,24.870555555555555,18.8625,24.870555555555555,17.884444444444444,50.300000000000004 +24.919999999999998,18.2,24.919999999999998,18.9,24.919999999999998,17.92,50.400000000000006 +24.969444444444445,18.23611111111111,24.969444444444445,18.9375,24.969444444444445,17.955555555555556,50.5 +25.01888888888889,18.272222222222222,25.01888888888889,18.974999999999998,25.01888888888889,17.99111111111111,50.6 +25.06833333333333,18.30833333333333,25.06833333333333,19.0125,25.06833333333333,18.026666666666667,50.7 +25.11777777777778,18.34444444444444,25.11777777777778,19.05,25.11777777777778,18.06222222222222,50.800000000000004 +25.16722222222222,18.380555555555553,25.16722222222222,19.0875,25.16722222222222,18.09777777777778,50.900000000000006 +25.216666666666665,18.416666666666664,25.216666666666665,19.125,25.216666666666665,18.133333333333333,51.0 +25.266111111111112,18.452777777777776,25.266111111111112,19.162499999999998,25.266111111111112,18.16888888888889,51.1 +25.315555555555555,18.488888888888887,25.315555555555555,19.2,25.315555555555555,18.204444444444444,51.2 +25.365,18.525,25.365,19.2375,25.365,18.24,51.300000000000004 +25.414444444444445,18.56111111111111,25.414444444444445,19.275,25.414444444444445,18.275555555555556,51.400000000000006 +25.46388888888889,18.59722222222222,25.46388888888889,19.3125,25.46388888888889,18.31111111111111,51.5 +25.513333333333332,18.633333333333333,25.513333333333332,19.349999999999998,25.513333333333332,18.346666666666668,51.6 +25.56277777777778,18.669444444444444,25.56277777777778,19.3875,25.56277777777778,18.38222222222222,51.7 +25.612222222222222,18.705555555555552,25.612222222222222,19.425,25.612222222222222,18.41777777777778,51.800000000000004 +25.661666666666665,18.741666666666664,25.661666666666665,19.4625,25.661666666666665,18.453333333333333,51.900000000000006 +25.711111111111112,18.777777777777775,25.711111111111112,19.5,25.711111111111112,18.488888888888887,52.0 +25.760555555555555,18.813888888888886,25.760555555555555,19.537499999999998,25.760555555555555,18.524444444444445,52.1 +25.81,18.849999999999998,25.81,19.575,25.81,18.56,52.2 +25.859444444444446,18.88611111111111,25.859444444444446,19.6125,25.859444444444446,18.595555555555556,52.300000000000004 +25.90888888888889,18.92222222222222,25.90888888888889,19.65,25.90888888888889,18.63111111111111,52.400000000000006 +25.958333333333332,18.958333333333332,25.958333333333332,19.6875,25.958333333333332,18.666666666666668,52.5 +26.00777777777778,18.994444444444444,26.00777777777778,19.724999999999998,26.00777777777778,18.702222222222222,52.6 +26.057222222222222,19.030555555555555,26.057222222222222,19.7625,26.057222222222222,18.73777777777778,52.7 +26.106666666666666,19.066666666666666,26.106666666666666,19.8,26.106666666666666,18.773333333333333,52.800000000000004 +26.156111111111112,19.102777777777774,26.156111111111112,19.8375,26.156111111111112,18.808888888888887,52.900000000000006 +26.205555555555556,19.138888888888886,26.205555555555556,19.875,26.205555555555556,18.844444444444445,53.0 +26.255,19.174999999999997,26.255,19.912499999999998,26.255,18.88,53.1 +26.304444444444442,19.21111111111111,26.304444444444442,19.95,26.304444444444442,18.915555555555557,53.2 +26.35388888888889,19.24722222222222,26.35388888888889,19.9875,26.35388888888889,18.95111111111111,53.300000000000004 +26.403333333333332,19.28333333333333,26.403333333333332,20.025,26.403333333333332,18.986666666666668,53.400000000000006 +26.452777777777776,19.319444444444443,26.452777777777776,20.0625,26.452777777777776,19.022222222222222,53.5 +26.502222222222223,19.355555555555554,26.502222222222223,20.099999999999998,26.502222222222223,19.057777777777776,53.6 +26.551666666666666,19.391666666666666,26.551666666666666,20.1375,26.551666666666666,19.093333333333334,53.7 +26.60111111111111,19.427777777777777,26.60111111111111,20.175,26.60111111111111,19.128888888888888,53.800000000000004 +26.650555555555556,19.46388888888889,26.650555555555556,20.2125,26.650555555555556,19.164444444444445,53.900000000000006 +26.7,19.499999999999996,26.7,20.25,26.7,19.2,54.0 +26.749444444444443,19.536111111111108,26.749444444444443,20.287499999999998,26.749444444444443,19.235555555555557,54.1 +26.79888888888889,19.57222222222222,26.79888888888889,20.325,26.79888888888889,19.27111111111111,54.2 +26.848333333333333,19.60833333333333,26.848333333333333,20.3625,26.848333333333333,19.30666666666667,54.300000000000004 +26.897777777777776,19.644444444444442,26.897777777777776,20.4,26.897777777777776,19.342222222222222,54.400000000000006 +26.947222222222223,19.680555555555554,26.947222222222223,20.4375,26.947222222222223,19.377777777777776,54.5 +26.996666666666666,19.716666666666665,26.996666666666666,20.474999999999998,26.996666666666666,19.413333333333334,54.6 +27.04611111111111,19.752777777777776,27.04611111111111,20.5125,27.04611111111111,19.448888888888888,54.7 +27.095555555555556,19.788888888888888,27.095555555555556,20.55,27.095555555555556,19.484444444444446,54.800000000000004 +27.145,19.825,27.145,20.5875,27.145,19.52,54.900000000000006 +27.194444444444443,19.86111111111111,27.194444444444443,20.625,27.194444444444443,19.555555555555557,55.0 +27.24388888888889,19.89722222222222,27.24388888888889,20.662499999999998,27.24388888888889,19.59111111111111,55.1 +27.293333333333333,19.93333333333333,27.293333333333333,20.7,27.293333333333333,19.626666666666665,55.2 +27.342777777777776,19.96944444444444,27.342777777777776,20.7375,27.342777777777776,19.662222222222223,55.300000000000004 +27.392222222222223,20.005555555555553,27.392222222222223,20.775,27.392222222222223,19.697777777777777,55.400000000000006 +27.441666666666666,20.041666666666664,27.441666666666666,20.8125,27.441666666666666,19.733333333333334,55.5 +27.49111111111111,20.077777777777776,27.49111111111111,20.849999999999998,27.49111111111111,19.76888888888889,55.6 +27.540555555555557,20.113888888888887,27.540555555555557,20.8875,27.540555555555557,19.804444444444446,55.7 +27.59,20.15,27.59,20.925,27.59,19.84,55.800000000000004 +27.639444444444443,20.18611111111111,27.639444444444443,20.9625,27.639444444444443,19.875555555555554,55.900000000000006 +27.68888888888889,20.22222222222222,27.68888888888889,21.0,27.68888888888889,19.91111111111111,56.0 +27.738333333333333,20.258333333333333,27.738333333333333,21.037499999999998,27.738333333333333,19.946666666666665,56.1 +27.787777777777777,20.294444444444444,27.787777777777777,21.075,27.787777777777777,19.982222222222223,56.2 +27.837222222222223,20.330555555555552,27.837222222222223,21.1125,27.837222222222223,20.017777777777777,56.300000000000004 +27.886666666666667,20.366666666666664,27.886666666666667,21.15,27.886666666666667,20.053333333333335,56.400000000000006 +27.93611111111111,20.402777777777775,27.93611111111111,21.1875,27.93611111111111,20.08888888888889,56.5 +27.985555555555557,20.438888888888886,27.985555555555557,21.224999999999998,27.985555555555557,20.124444444444446,56.6 +28.035,20.474999999999998,28.035,21.2625,28.035,20.16,56.7 +28.084444444444443,20.51111111111111,28.084444444444443,21.3,28.084444444444443,20.195555555555554,56.800000000000004 +28.133888888888887,20.54722222222222,28.133888888888887,21.3375,28.133888888888887,20.23111111111111,56.900000000000006 +28.183333333333334,20.583333333333332,28.183333333333334,21.375,28.183333333333334,20.266666666666666,57.0 +28.232777777777777,20.619444444444444,28.232777777777777,21.412499999999998,28.232777777777777,20.302222222222223,57.1 +28.28222222222222,20.655555555555555,28.28222222222222,21.45,28.28222222222222,20.337777777777777,57.2 +28.331666666666667,20.691666666666666,28.331666666666667,21.4875,28.331666666666667,20.373333333333335,57.300000000000004 +28.38111111111111,20.727777777777774,28.38111111111111,21.525,28.38111111111111,20.40888888888889,57.400000000000006 +28.430555555555554,20.763888888888886,28.430555555555554,21.5625,28.430555555555554,20.444444444444443,57.5 +28.48,20.799999999999997,28.48,21.599999999999998,28.48,20.48,57.6 +28.529444444444444,20.83611111111111,28.529444444444444,21.6375,28.529444444444444,20.515555555555554,57.7 +28.578888888888887,20.87222222222222,28.578888888888887,21.675,28.578888888888887,20.551111111111112,57.800000000000004 +28.628333333333334,20.90833333333333,28.628333333333334,21.7125,28.628333333333334,20.586666666666666,57.900000000000006 +28.677777777777777,20.944444444444443,28.677777777777777,21.75,28.677777777777777,20.622222222222224,58.0 +28.72722222222222,20.980555555555554,28.72722222222222,21.787499999999998,28.72722222222222,20.657777777777778,58.1 +28.776666666666667,21.016666666666666,28.776666666666667,21.825,28.776666666666667,20.69333333333333,58.2 +28.82611111111111,21.052777777777777,28.82611111111111,21.8625,28.82611111111111,20.72888888888889,58.300000000000004 +28.875555555555554,21.08888888888889,28.875555555555554,21.9,28.875555555555554,20.764444444444443,58.400000000000006 +28.925,21.124999999999996,28.925,21.9375,28.925,20.8,58.5 +28.974444444444444,21.161111111111108,28.974444444444444,21.974999999999998,28.974444444444444,20.835555555555555,58.6 +29.023888888888887,21.19722222222222,29.023888888888887,22.0125,29.023888888888887,20.871111111111112,58.7 +29.073333333333334,21.23333333333333,29.073333333333334,22.05,29.073333333333334,20.906666666666666,58.800000000000004 +29.122777777777777,21.269444444444442,29.122777777777777,22.0875,29.122777777777777,20.942222222222224,58.900000000000006 +29.17222222222222,21.305555555555554,29.17222222222222,22.125,29.17222222222222,20.977777777777778,59.0 +29.221666666666668,21.341666666666665,29.221666666666668,22.162499999999998,29.221666666666668,21.013333333333332,59.1 +29.27111111111111,21.377777777777776,29.27111111111111,22.2,29.27111111111111,21.04888888888889,59.2 +29.320555555555554,21.413888888888888,29.320555555555554,22.2375,29.320555555555554,21.084444444444443,59.300000000000004 +29.37,21.45,29.37,22.275,29.37,21.12,59.400000000000006 +29.419444444444444,21.48611111111111,29.419444444444444,22.3125,29.419444444444444,21.155555555555555,59.5 +29.468888888888888,21.52222222222222,29.468888888888888,22.349999999999998,29.468888888888888,21.191111111111113,59.6 +29.518333333333334,21.55833333333333,29.518333333333334,22.3875,29.518333333333334,21.226666666666667,59.7 +29.567777777777778,21.59444444444444,29.567777777777778,22.425,29.567777777777778,21.26222222222222,59.800000000000004 +29.61722222222222,21.630555555555553,29.61722222222222,22.4625,29.61722222222222,21.297777777777778,59.900000000000006 +29.666666666666668,21.666666666666664,29.666666666666668,22.5,29.666666666666668,21.333333333333332,60.0 +29.71611111111111,21.702777777777776,29.71611111111111,22.537499999999998,29.71611111111111,21.36888888888889,60.1 +29.765555555555554,21.738888888888887,29.765555555555554,22.575,29.765555555555554,21.404444444444444,60.2 +29.815,21.775,29.815,22.6125,29.815,21.44,60.300000000000004 +29.864444444444445,21.81111111111111,29.864444444444445,22.65,29.864444444444445,21.475555555555555,60.400000000000006 +29.913888888888888,21.84722222222222,29.913888888888888,22.6875,29.913888888888888,21.511111111111113,60.5 +29.96333333333333,21.883333333333333,29.96333333333333,22.724999999999998,29.96333333333333,21.546666666666667,60.6 +30.012777777777778,21.91944444444444,30.012777777777778,22.7625,30.012777777777778,21.58222222222222,60.7 +30.06222222222222,21.955555555555552,30.06222222222222,22.8,30.06222222222222,21.61777777777778,60.800000000000004 +30.111666666666665,21.991666666666664,30.111666666666665,22.8375,30.111666666666665,21.653333333333332,60.900000000000006 +30.16111111111111,22.027777777777775,30.16111111111111,22.875,30.16111111111111,21.68888888888889,61.0 +30.210555555555555,22.063888888888886,30.210555555555555,22.912499999999998,30.210555555555555,21.724444444444444,61.1 +30.259999999999998,22.099999999999998,30.259999999999998,22.95,30.259999999999998,21.76,61.2 +30.309444444444445,22.13611111111111,30.309444444444445,22.9875,30.309444444444445,21.795555555555556,61.300000000000004 +30.358888888888888,22.17222222222222,30.358888888888888,23.025,30.358888888888888,21.83111111111111,61.400000000000006 +30.40833333333333,22.208333333333332,30.40833333333333,23.0625,30.40833333333333,21.866666666666667,61.5 +30.45777777777778,22.244444444444444,30.45777777777778,23.099999999999998,30.45777777777778,21.90222222222222,61.6 +30.50722222222222,22.280555555555555,30.50722222222222,23.1375,30.50722222222222,21.93777777777778,61.7 +30.556666666666665,22.316666666666663,30.556666666666665,23.175,30.556666666666665,21.973333333333333,61.800000000000004 +30.60611111111111,22.352777777777774,30.60611111111111,23.2125,30.60611111111111,22.00888888888889,61.900000000000006 +30.655555555555555,22.388888888888886,30.655555555555555,23.25,30.655555555555555,22.044444444444444,62.0 +30.705,22.424999999999997,30.705,23.287499999999998,30.705,22.08,62.1 +30.754444444444445,22.46111111111111,30.754444444444445,23.325,30.754444444444445,22.115555555555556,62.2 +30.80388888888889,22.49722222222222,30.80388888888889,23.3625,30.80388888888889,22.15111111111111,62.300000000000004 +30.85333333333333,22.53333333333333,30.85333333333333,23.4,30.85333333333333,22.186666666666667,62.400000000000006 +30.90277777777778,22.569444444444443,30.90277777777778,23.4375,30.90277777777778,22.22222222222222,62.5 +30.952222222222222,22.605555555555554,30.952222222222222,23.474999999999998,30.952222222222222,22.25777777777778,62.6 +31.001666666666665,22.641666666666666,31.001666666666665,23.5125,31.001666666666665,22.293333333333333,62.7 +31.051111111111112,22.677777777777777,31.051111111111112,23.55,31.051111111111112,22.32888888888889,62.800000000000004 +31.100555555555555,22.713888888888885,31.100555555555555,23.5875,31.100555555555555,22.364444444444445,62.900000000000006 +31.15,22.749999999999996,31.15,23.625,31.15,22.4,63.0 +31.199444444444445,22.786111111111108,31.199444444444445,23.662499999999998,31.199444444444445,22.435555555555556,63.1 +31.24888888888889,22.82222222222222,31.24888888888889,23.7,31.24888888888889,22.47111111111111,63.2 +31.298333333333332,22.85833333333333,31.298333333333332,23.7375,31.298333333333332,22.506666666666668,63.300000000000004 +31.34777777777778,22.894444444444442,31.34777777777778,23.775,31.34777777777778,22.54222222222222,63.400000000000006 +31.397222222222222,22.930555555555554,31.397222222222222,23.8125,31.397222222222222,22.57777777777778,63.5 +31.446666666666665,22.966666666666665,31.446666666666665,23.849999999999998,31.446666666666665,22.613333333333333,63.6 +31.496111111111112,23.002777777777776,31.496111111111112,23.8875,31.496111111111112,22.648888888888887,63.7 +31.545555555555556,23.038888888888888,31.545555555555556,23.925,31.545555555555556,22.684444444444445,63.800000000000004 +31.595,23.075,31.595,23.9625,31.595,22.72,63.900000000000006 +31.644444444444446,23.111111111111107,31.644444444444446,24.0,31.644444444444446,22.755555555555556,64.0 +31.69388888888889,23.14722222222222,31.69388888888889,24.037499999999998,31.69388888888889,22.79111111111111,64.10000000000001 +31.743333333333332,23.18333333333333,31.743333333333332,24.075,31.743333333333332,22.826666666666668,64.2 +31.792777777777776,23.21944444444444,31.792777777777776,24.1125,31.792777777777776,22.862222222222222,64.3 +31.842222222222222,23.255555555555553,31.842222222222222,24.15,31.842222222222222,22.897777777777776,64.4 +31.891666666666666,23.291666666666664,31.891666666666666,24.1875,31.891666666666666,22.933333333333334,64.5 +31.94111111111111,23.327777777777776,31.94111111111111,24.224999999999998,31.94111111111111,22.968888888888888,64.60000000000001 +31.990555555555556,23.363888888888887,31.990555555555556,24.2625,31.990555555555556,23.004444444444445,64.7 +32.04,23.4,32.04,24.3,32.04,23.04,64.8 +32.089444444444446,23.43611111111111,32.089444444444446,24.3375,32.089444444444446,23.075555555555557,64.9 +32.138888888888886,23.47222222222222,32.138888888888886,24.375,32.138888888888886,23.11111111111111,65.0 +32.18833333333333,23.508333333333333,32.18833333333333,24.412499999999998,32.18833333333333,23.14666666666667,65.10000000000001 +32.23777777777778,23.54444444444444,32.23777777777778,24.45,32.23777777777778,23.182222222222222,65.2 +32.28722222222222,23.580555555555552,32.28722222222222,24.4875,32.28722222222222,23.217777777777776,65.3 +32.336666666666666,23.616666666666664,32.336666666666666,24.525,32.336666666666666,23.253333333333334,65.4 +32.38611111111111,23.652777777777775,32.38611111111111,24.5625,32.38611111111111,23.288888888888888,65.5 +32.43555555555555,23.688888888888886,32.43555555555555,24.599999999999998,32.43555555555555,23.324444444444445,65.60000000000001 +32.485,23.724999999999998,32.485,24.6375,32.485,23.36,65.7 +32.534444444444446,23.76111111111111,32.534444444444446,24.675,32.534444444444446,23.395555555555557,65.8 +32.583888888888886,23.79722222222222,32.583888888888886,24.7125,32.583888888888886,23.43111111111111,65.9 +32.63333333333333,23.833333333333332,32.63333333333333,24.75,32.63333333333333,23.466666666666665,66.0 +32.68277777777778,23.869444444444444,32.68277777777778,24.787499999999998,32.68277777777778,23.502222222222223,66.10000000000001 +32.73222222222222,23.905555555555555,32.73222222222222,24.825,32.73222222222222,23.537777777777777,66.2 +32.781666666666666,23.941666666666663,32.781666666666666,24.8625,32.781666666666666,23.573333333333334,66.3 +32.83111111111111,23.977777777777774,32.83111111111111,24.9,32.83111111111111,23.608888888888888,66.4 +32.88055555555555,24.013888888888886,32.88055555555555,24.9375,32.88055555555555,23.644444444444446,66.5 +32.93,24.049999999999997,32.93,24.974999999999998,32.93,23.68,66.60000000000001 +32.97944444444445,24.08611111111111,32.97944444444445,25.0125,32.97944444444445,23.715555555555557,66.7 +33.028888888888886,24.12222222222222,33.028888888888886,25.05,33.028888888888886,23.75111111111111,66.8 +33.07833333333333,24.15833333333333,33.07833333333333,25.0875,33.07833333333333,23.786666666666665,66.9 +33.12777777777778,24.194444444444443,33.12777777777778,25.125,33.12777777777778,23.822222222222223,67.0 +33.17722222222222,24.230555555555554,33.17722222222222,25.162499999999998,33.17722222222222,23.857777777777777,67.10000000000001 +33.22666666666667,24.266666666666666,33.22666666666667,25.2,33.22666666666667,23.893333333333334,67.2 +33.27611111111111,24.302777777777777,33.27611111111111,25.2375,33.27611111111111,23.92888888888889,67.3 +33.32555555555555,24.338888888888885,33.32555555555555,25.275,33.32555555555555,23.964444444444446,67.4 +33.375,24.374999999999996,33.375,25.3125,33.375,24.0,67.5 +33.42444444444445,24.411111111111108,33.42444444444445,25.349999999999998,33.42444444444445,24.035555555555554,67.60000000000001 +33.47388888888889,24.44722222222222,33.47388888888889,25.3875,33.47388888888889,24.07111111111111,67.7 +33.52333333333333,24.48333333333333,33.52333333333333,25.425,33.52333333333333,24.106666666666666,67.8 +33.57277777777778,24.519444444444442,33.57277777777778,25.4625,33.57277777777778,24.142222222222223,67.9 +33.62222222222222,24.555555555555554,33.62222222222222,25.5,33.62222222222222,24.177777777777777,68.0 +33.67166666666667,24.591666666666665,33.67166666666667,25.537499999999998,33.67166666666667,24.213333333333335,68.10000000000001 +33.721111111111114,24.627777777777776,33.721111111111114,25.575,33.721111111111114,24.24888888888889,68.2 +33.77055555555555,24.663888888888888,33.77055555555555,25.6125,33.77055555555555,24.284444444444443,68.3 +33.82,24.7,33.82,25.65,33.82,24.32,68.4 +33.86944444444445,24.736111111111107,33.86944444444445,25.6875,33.86944444444445,24.355555555555554,68.5 +33.91888888888889,24.77222222222222,33.91888888888889,25.724999999999998,33.91888888888889,24.391111111111112,68.60000000000001 +33.968333333333334,24.80833333333333,33.968333333333334,25.7625,33.968333333333334,24.426666666666666,68.7 +34.01777777777778,24.84444444444444,34.01777777777778,25.8,34.01777777777778,24.462222222222223,68.8 +34.06722222222222,24.880555555555553,34.06722222222222,25.8375,34.06722222222222,24.497777777777777,68.9 +34.11666666666667,24.916666666666664,34.11666666666667,25.875,34.11666666666667,24.533333333333335,69.0 +34.166111111111114,24.952777777777776,34.166111111111114,25.912499999999998,34.166111111111114,24.56888888888889,69.10000000000001 +34.215555555555554,24.988888888888887,34.215555555555554,25.95,34.215555555555554,24.604444444444443,69.2 +34.265,25.025,34.265,25.9875,34.265,24.64,69.3 +34.31444444444445,25.06111111111111,34.31444444444445,26.025,34.31444444444445,24.675555555555555,69.4 +34.36388888888889,25.09722222222222,34.36388888888889,26.0625,34.36388888888889,24.711111111111112,69.5 +34.413333333333334,25.13333333333333,34.413333333333334,26.099999999999998,34.413333333333334,24.746666666666666,69.60000000000001 +34.462777777777774,25.16944444444444,34.462777777777774,26.1375,34.462777777777774,24.782222222222224,69.7 +34.51222222222222,25.205555555555552,34.51222222222222,26.175,34.51222222222222,24.817777777777778,69.8 +34.56166666666667,25.241666666666664,34.56166666666667,26.2125,34.56166666666667,24.85333333333333,69.9 +34.61111111111111,25.277777777777775,34.61111111111111,26.25,34.61111111111111,24.88888888888889,70.0 +34.660555555555554,25.313888888888886,34.660555555555554,26.287499999999998,34.660555555555554,24.924444444444443,70.10000000000001 +34.71,25.349999999999998,34.71,26.325,34.71,24.96,70.2 +34.75944444444444,25.38611111111111,34.75944444444444,26.3625,34.75944444444444,24.995555555555555,70.3 +34.80888888888889,25.42222222222222,34.80888888888889,26.4,34.80888888888889,25.031111111111112,70.4 +34.858333333333334,25.458333333333332,34.858333333333334,26.4375,34.858333333333334,25.066666666666666,70.5 +34.907777777777774,25.494444444444444,34.907777777777774,26.474999999999998,34.907777777777774,25.10222222222222,70.60000000000001 +34.95722222222222,25.53055555555555,34.95722222222222,26.5125,34.95722222222222,25.137777777777778,70.7 +35.00666666666667,25.566666666666663,35.00666666666667,26.55,35.00666666666667,25.173333333333332,70.8 +35.05611111111111,25.602777777777774,35.05611111111111,26.5875,35.05611111111111,25.20888888888889,70.9 +35.105555555555554,25.638888888888886,35.105555555555554,26.625,35.105555555555554,25.244444444444444,71.0 +35.155,25.674999999999997,35.155,26.662499999999998,35.155,25.28,71.10000000000001 +35.20444444444444,25.71111111111111,35.20444444444444,26.7,35.20444444444444,25.315555555555555,71.2 +35.25388888888889,25.74722222222222,35.25388888888889,26.7375,35.25388888888889,25.351111111111113,71.3 +35.303333333333335,25.78333333333333,35.303333333333335,26.775,35.303333333333335,25.386666666666667,71.4 +35.352777777777774,25.819444444444443,35.352777777777774,26.8125,35.352777777777774,25.42222222222222,71.5 +35.40222222222222,25.855555555555554,35.40222222222222,26.849999999999998,35.40222222222222,25.45777777777778,71.60000000000001 +35.45166666666667,25.891666666666666,35.45166666666667,26.8875,35.45166666666667,25.493333333333332,71.7 +35.50111111111111,25.927777777777774,35.50111111111111,26.925,35.50111111111111,25.52888888888889,71.8 +35.550555555555555,25.963888888888885,35.550555555555555,26.9625,35.550555555555555,25.564444444444444,71.9 +35.6,25.999999999999996,35.6,27.0,35.6,25.6,72.0 +35.64944444444444,26.036111111111108,35.64944444444444,27.037499999999998,35.64944444444444,25.635555555555555,72.10000000000001 +35.69888888888889,26.07222222222222,35.69888888888889,27.075,35.69888888888889,25.67111111111111,72.2 +35.748333333333335,26.10833333333333,35.748333333333335,27.1125,35.748333333333335,25.706666666666667,72.3 +35.797777777777775,26.144444444444442,35.797777777777775,27.15,35.797777777777775,25.74222222222222,72.4 +35.84722222222222,26.180555555555554,35.84722222222222,27.1875,35.84722222222222,25.77777777777778,72.5 +35.89666666666667,26.216666666666665,35.89666666666667,27.224999999999998,35.89666666666667,25.813333333333333,72.60000000000001 +35.94611111111111,26.252777777777776,35.94611111111111,27.2625,35.94611111111111,25.84888888888889,72.7 +35.995555555555555,26.288888888888888,35.995555555555555,27.3,35.995555555555555,25.884444444444444,72.8 +36.045,26.325,36.045,27.3375,36.045,25.92,72.9 +36.09444444444444,26.361111111111107,36.09444444444444,27.375,36.09444444444444,25.955555555555556,73.0 +36.14388888888889,26.39722222222222,36.14388888888889,27.412499999999998,36.14388888888889,25.99111111111111,73.10000000000001 +36.193333333333335,26.43333333333333,36.193333333333335,27.45,36.193333333333335,26.026666666666667,73.2 +36.242777777777775,26.46944444444444,36.242777777777775,27.4875,36.242777777777775,26.06222222222222,73.3 +36.29222222222222,26.505555555555553,36.29222222222222,27.525,36.29222222222222,26.09777777777778,73.4 +36.34166666666667,26.541666666666664,36.34166666666667,27.5625,36.34166666666667,26.133333333333333,73.5 +36.39111111111111,26.577777777777776,36.39111111111111,27.599999999999998,36.39111111111111,26.16888888888889,73.60000000000001 +36.440555555555555,26.613888888888887,36.440555555555555,27.6375,36.440555555555555,26.204444444444444,73.7 +36.49,26.65,36.49,27.675,36.49,26.24,73.8 +36.53944444444444,26.68611111111111,36.53944444444444,27.7125,36.53944444444444,26.275555555555556,73.9 +36.58888888888889,26.72222222222222,36.58888888888889,27.75,36.58888888888889,26.31111111111111,74.0 +36.638333333333335,26.75833333333333,36.638333333333335,27.787499999999998,36.638333333333335,26.346666666666668,74.10000000000001 +36.687777777777775,26.79444444444444,36.687777777777775,27.825,36.687777777777775,26.38222222222222,74.2 +36.73722222222222,26.830555555555552,36.73722222222222,27.8625,36.73722222222222,26.41777777777778,74.3 +36.78666666666667,26.866666666666664,36.78666666666667,27.9,36.78666666666667,26.453333333333333,74.4 +36.83611111111111,26.902777777777775,36.83611111111111,27.9375,36.83611111111111,26.488888888888887,74.5 +36.885555555555555,26.938888888888886,36.885555555555555,27.974999999999998,36.885555555555555,26.524444444444445,74.60000000000001 +36.935,26.974999999999998,36.935,28.0125,36.935,26.56,74.7 +36.98444444444444,27.01111111111111,36.98444444444444,28.05,36.98444444444444,26.595555555555556,74.8 +37.03388888888889,27.04722222222222,37.03388888888889,28.0875,37.03388888888889,26.63111111111111,74.9 +37.083333333333336,27.083333333333332,37.083333333333336,28.125,37.083333333333336,26.666666666666668,75.0 +37.132777777777775,27.119444444444444,37.132777777777775,28.162499999999998,37.132777777777775,26.702222222222222,75.10000000000001 +37.18222222222222,27.15555555555555,37.18222222222222,28.2,37.18222222222222,26.73777777777778,75.2 +37.23166666666667,27.191666666666663,37.23166666666667,28.2375,37.23166666666667,26.773333333333333,75.3 +37.28111111111111,27.227777777777774,37.28111111111111,28.275,37.28111111111111,26.808888888888887,75.4 +37.330555555555556,27.263888888888886,37.330555555555556,28.3125,37.330555555555556,26.844444444444445,75.5 +37.38,27.299999999999997,37.38,28.349999999999998,37.38,26.88,75.60000000000001 +37.42944444444444,27.33611111111111,37.42944444444444,28.3875,37.42944444444444,26.915555555555557,75.7 +37.47888888888889,27.37222222222222,37.47888888888889,28.425,37.47888888888889,26.95111111111111,75.8 +37.528333333333336,27.40833333333333,37.528333333333336,28.4625,37.528333333333336,26.986666666666668,75.9 +37.577777777777776,27.444444444444443,37.577777777777776,28.5,37.577777777777776,27.022222222222222,76.0 +37.62722222222222,27.480555555555554,37.62722222222222,28.537499999999998,37.62722222222222,27.057777777777776,76.10000000000001 +37.67666666666667,27.516666666666666,37.67666666666667,28.575,37.67666666666667,27.093333333333334,76.2 +37.72611111111111,27.552777777777774,37.72611111111111,28.6125,37.72611111111111,27.128888888888888,76.3 +37.775555555555556,27.588888888888885,37.775555555555556,28.65,37.775555555555556,27.164444444444445,76.4 +37.825,27.624999999999996,37.825,28.6875,37.825,27.2,76.5 +37.87444444444444,27.661111111111108,37.87444444444444,28.724999999999998,37.87444444444444,27.235555555555557,76.60000000000001 +37.92388888888889,27.69722222222222,37.92388888888889,28.7625,37.92388888888889,27.27111111111111,76.7 +37.97333333333333,27.73333333333333,37.97333333333333,28.799999999999997,37.97333333333333,27.306666666666665,76.80000000000001 +38.022777777777776,27.769444444444442,38.022777777777776,28.8375,38.022777777777776,27.342222222222222,76.9 +38.07222222222222,27.805555555555554,38.07222222222222,28.875,38.07222222222222,27.377777777777776,77.0 +38.12166666666666,27.841666666666665,38.12166666666666,28.912499999999998,38.12166666666666,27.413333333333334,77.10000000000001 +38.17111111111111,27.877777777777776,38.17111111111111,28.95,38.17111111111111,27.448888888888888,77.2 +38.220555555555556,27.913888888888888,38.220555555555556,28.987499999999997,38.220555555555556,27.484444444444446,77.30000000000001 +38.269999999999996,27.949999999999996,38.269999999999996,29.025,38.269999999999996,27.52,77.4 +38.31944444444444,27.986111111111107,38.31944444444444,29.0625,38.31944444444444,27.555555555555557,77.5 +38.36888888888889,28.02222222222222,38.36888888888889,29.099999999999998,38.36888888888889,27.59111111111111,77.60000000000001 +38.41833333333333,28.05833333333333,38.41833333333333,29.1375,38.41833333333333,27.626666666666665,77.7 +38.467777777777776,28.09444444444444,38.467777777777776,29.174999999999997,38.467777777777776,27.662222222222223,77.80000000000001 +38.51722222222222,28.130555555555553,38.51722222222222,29.2125,38.51722222222222,27.697777777777777,77.9 +38.56666666666666,28.166666666666664,38.56666666666666,29.25,38.56666666666666,27.733333333333334,78.0 +38.61611111111111,28.202777777777776,38.61611111111111,29.287499999999998,38.61611111111111,27.76888888888889,78.10000000000001 +38.66555555555556,28.238888888888887,38.66555555555556,29.325,38.66555555555556,27.804444444444446,78.2 +38.714999999999996,28.275,38.714999999999996,29.362499999999997,38.714999999999996,27.84,78.30000000000001 +38.76444444444444,28.31111111111111,38.76444444444444,29.4,38.76444444444444,27.875555555555554,78.4 +38.81388888888889,28.347222222222218,38.81388888888889,29.4375,38.81388888888889,27.91111111111111,78.5 +38.86333333333333,28.38333333333333,38.86333333333333,29.474999999999998,38.86333333333333,27.946666666666665,78.60000000000001 +38.91277777777778,28.41944444444444,38.91277777777778,29.5125,38.91277777777778,27.982222222222223,78.7 +38.96222222222222,28.455555555555552,38.96222222222222,29.549999999999997,38.96222222222222,28.017777777777777,78.80000000000001 +39.01166666666666,28.491666666666664,39.01166666666666,29.5875,39.01166666666666,28.053333333333335,78.9 +39.06111111111111,28.527777777777775,39.06111111111111,29.625,39.06111111111111,28.08888888888889,79.0 +39.11055555555556,28.563888888888886,39.11055555555556,29.662499999999998,39.11055555555556,28.124444444444446,79.10000000000001 +39.16,28.599999999999998,39.16,29.7,39.16,28.16,79.2 +39.20944444444444,28.63611111111111,39.20944444444444,29.737499999999997,39.20944444444444,28.195555555555554,79.30000000000001 +39.25888888888889,28.67222222222222,39.25888888888889,29.775,39.25888888888889,28.23111111111111,79.4 +39.30833333333333,28.708333333333332,39.30833333333333,29.8125,39.30833333333333,28.266666666666666,79.5 +39.35777777777778,28.74444444444444,39.35777777777778,29.849999999999998,39.35777777777778,28.302222222222223,79.60000000000001 +39.407222222222224,28.78055555555555,39.407222222222224,29.8875,39.407222222222224,28.337777777777777,79.7 +39.45666666666666,28.816666666666663,39.45666666666666,29.924999999999997,39.45666666666666,28.373333333333335,79.80000000000001 +39.50611111111111,28.852777777777774,39.50611111111111,29.9625,39.50611111111111,28.40888888888889,79.9 +39.55555555555556,28.888888888888886,39.55555555555556,30.0,39.55555555555556,28.444444444444443,80.0 +39.605,28.924999999999997,39.605,30.037499999999998,39.605,28.48,80.10000000000001 +39.654444444444444,28.96111111111111,39.654444444444444,30.075,39.654444444444444,28.515555555555554,80.2 +39.70388888888889,28.99722222222222,39.70388888888889,30.112499999999997,39.70388888888889,28.551111111111112,80.30000000000001 +39.75333333333333,29.03333333333333,39.75333333333333,30.15,39.75333333333333,28.586666666666666,80.4 +39.80277777777778,29.069444444444443,39.80277777777778,30.1875,39.80277777777778,28.622222222222224,80.5 +39.852222222222224,29.105555555555554,39.852222222222224,30.224999999999998,39.852222222222224,28.657777777777778,80.60000000000001 +39.901666666666664,29.141666666666662,39.901666666666664,30.2625,39.901666666666664,28.69333333333333,80.7 +39.95111111111111,29.177777777777774,39.95111111111111,30.299999999999997,39.95111111111111,28.72888888888889,80.80000000000001 +40.00055555555556,29.213888888888885,40.00055555555556,30.3375,40.00055555555556,28.764444444444443,80.9 +40.05,29.249999999999996,40.05,30.375,40.05,28.8,81.0 +40.099444444444444,29.286111111111108,40.099444444444444,30.412499999999998,40.099444444444444,28.835555555555555,81.10000000000001 +40.14888888888889,29.32222222222222,40.14888888888889,30.45,40.14888888888889,28.871111111111112,81.2 +40.19833333333333,29.35833333333333,40.19833333333333,30.487499999999997,40.19833333333333,28.906666666666666,81.30000000000001 +40.24777777777778,29.394444444444442,40.24777777777778,30.525,40.24777777777778,28.942222222222224,81.4 +40.297222222222224,29.430555555555554,40.297222222222224,30.5625,40.297222222222224,28.977777777777778,81.5 +40.346666666666664,29.466666666666665,40.346666666666664,30.599999999999998,40.346666666666664,29.013333333333332,81.60000000000001 +40.39611111111111,29.502777777777776,40.39611111111111,30.6375,40.39611111111111,29.04888888888889,81.7 +40.44555555555556,29.538888888888888,40.44555555555556,30.674999999999997,40.44555555555556,29.084444444444443,81.80000000000001 +40.495,29.574999999999996,40.495,30.7125,40.495,29.12,81.9 +40.544444444444444,29.611111111111107,40.544444444444444,30.75,40.544444444444444,29.155555555555555,82.0 +40.59388888888889,29.64722222222222,40.59388888888889,30.787499999999998,40.59388888888889,29.191111111111113,82.10000000000001 +40.64333333333333,29.68333333333333,40.64333333333333,30.825,40.64333333333333,29.226666666666667,82.2 +40.69277777777778,29.71944444444444,40.69277777777778,30.862499999999997,40.69277777777778,29.26222222222222,82.30000000000001 +40.742222222222225,29.755555555555553,40.742222222222225,30.9,40.742222222222225,29.297777777777778,82.4 +40.791666666666664,29.791666666666664,40.791666666666664,30.9375,40.791666666666664,29.333333333333332,82.5 +40.84111111111111,29.827777777777776,40.84111111111111,30.974999999999998,40.84111111111111,29.36888888888889,82.60000000000001 +40.89055555555556,29.863888888888887,40.89055555555556,31.0125,40.89055555555556,29.404444444444444,82.7 +40.94,29.9,40.94,31.049999999999997,40.94,29.44,82.80000000000001 +40.989444444444445,29.93611111111111,40.989444444444445,31.0875,40.989444444444445,29.475555555555555,82.9 +41.03888888888889,29.972222222222218,41.03888888888889,31.125,41.03888888888889,29.511111111111113,83.0 +41.08833333333333,30.00833333333333,41.08833333333333,31.162499999999998,41.08833333333333,29.546666666666667,83.10000000000001 +41.13777777777778,30.04444444444444,41.13777777777778,31.2,41.13777777777778,29.58222222222222,83.2 +41.187222222222225,30.080555555555552,41.187222222222225,31.237499999999997,41.187222222222225,29.61777777777778,83.30000000000001 +41.236666666666665,30.116666666666664,41.236666666666665,31.275,41.236666666666665,29.653333333333332,83.4 +41.28611111111111,30.152777777777775,41.28611111111111,31.3125,41.28611111111111,29.68888888888889,83.5 +41.33555555555556,30.188888888888886,41.33555555555556,31.349999999999998,41.33555555555556,29.724444444444444,83.60000000000001 +41.385,30.224999999999998,41.385,31.3875,41.385,29.76,83.7 +41.434444444444445,30.26111111111111,41.434444444444445,31.424999999999997,41.434444444444445,29.795555555555556,83.80000000000001 +41.48388888888889,30.29722222222222,41.48388888888889,31.4625,41.48388888888889,29.83111111111111,83.9 +41.53333333333333,30.333333333333332,41.53333333333333,31.5,41.53333333333333,29.866666666666667,84.0 +41.58277777777778,30.36944444444444,41.58277777777778,31.537499999999998,41.58277777777778,29.90222222222222,84.10000000000001 +41.63222222222222,30.40555555555555,41.63222222222222,31.575,41.63222222222222,29.93777777777778,84.2 +41.681666666666665,30.441666666666663,41.681666666666665,31.612499999999997,41.681666666666665,29.973333333333333,84.30000000000001 +41.73111111111111,30.477777777777774,41.73111111111111,31.65,41.73111111111111,30.00888888888889,84.4 +41.78055555555555,30.513888888888886,41.78055555555555,31.6875,41.78055555555555,30.044444444444444,84.5 +41.83,30.549999999999997,41.83,31.724999999999998,41.83,30.08,84.60000000000001 +41.879444444444445,30.58611111111111,41.879444444444445,31.7625,41.879444444444445,30.115555555555556,84.7 +41.928888888888885,30.62222222222222,41.928888888888885,31.799999999999997,41.928888888888885,30.15111111111111,84.80000000000001 +41.97833333333333,30.65833333333333,41.97833333333333,31.8375,41.97833333333333,30.186666666666667,84.9 +42.02777777777778,30.694444444444443,42.02777777777778,31.875,42.02777777777778,30.22222222222222,85.0 +42.07722222222222,30.730555555555554,42.07722222222222,31.912499999999998,42.07722222222222,30.25777777777778,85.10000000000001 +42.126666666666665,30.766666666666662,42.126666666666665,31.95,42.126666666666665,30.293333333333333,85.2 +42.17611111111111,30.802777777777774,42.17611111111111,31.987499999999997,42.17611111111111,30.32888888888889,85.30000000000001 +42.22555555555555,30.838888888888885,42.22555555555555,32.025,42.22555555555555,30.364444444444445,85.4 +42.275,30.874999999999996,42.275,32.0625,42.275,30.4,85.5 +42.324444444444445,30.911111111111108,42.324444444444445,32.1,42.324444444444445,30.435555555555556,85.60000000000001 +42.373888888888885,30.94722222222222,42.373888888888885,32.137499999999996,42.373888888888885,30.47111111111111,85.7 +42.42333333333333,30.98333333333333,42.42333333333333,32.175,42.42333333333333,30.506666666666668,85.80000000000001 +42.47277777777778,31.019444444444442,42.47277777777778,32.2125,42.47277777777778,30.54222222222222,85.9 +42.52222222222222,31.055555555555554,42.52222222222222,32.25,42.52222222222222,30.57777777777778,86.0 +42.571666666666665,31.091666666666665,42.571666666666665,32.2875,42.571666666666665,30.613333333333333,86.10000000000001 +42.62111111111111,31.127777777777776,42.62111111111111,32.324999999999996,42.62111111111111,30.648888888888887,86.2 +42.67055555555555,31.163888888888884,42.67055555555555,32.3625,42.67055555555555,30.684444444444445,86.30000000000001 +42.72,31.199999999999996,42.72,32.4,42.72,30.72,86.4 +42.769444444444446,31.236111111111107,42.769444444444446,32.4375,42.769444444444446,30.755555555555556,86.5 +42.818888888888885,31.27222222222222,42.818888888888885,32.475,42.818888888888885,30.79111111111111,86.60000000000001 +42.86833333333333,31.30833333333333,42.86833333333333,32.512499999999996,42.86833333333333,30.826666666666668,86.7 +42.91777777777778,31.34444444444444,42.91777777777778,32.55,42.91777777777778,30.862222222222222,86.80000000000001 +42.96722222222222,31.380555555555553,42.96722222222222,32.5875,42.96722222222222,30.897777777777776,86.9 +43.016666666666666,31.416666666666664,43.016666666666666,32.625,43.016666666666666,30.933333333333334,87.0 +43.06611111111111,31.452777777777776,43.06611111111111,32.6625,43.06611111111111,30.968888888888888,87.10000000000001 +43.11555555555555,31.488888888888887,43.11555555555555,32.699999999999996,43.11555555555555,31.004444444444445,87.2 +43.165,31.525,43.165,32.7375,43.165,31.04,87.30000000000001 +43.214444444444446,31.561111111111106,43.214444444444446,32.775,43.214444444444446,31.075555555555557,87.4 +43.263888888888886,31.597222222222218,43.263888888888886,32.8125,43.263888888888886,31.11111111111111,87.5 +43.31333333333333,31.63333333333333,43.31333333333333,32.85,43.31333333333333,31.14666666666667,87.60000000000001 +43.36277777777778,31.66944444444444,43.36277777777778,32.887499999999996,43.36277777777778,31.182222222222222,87.7 +43.41222222222222,31.705555555555552,43.41222222222222,32.925,43.41222222222222,31.217777777777776,87.80000000000001 +43.461666666666666,31.741666666666664,43.461666666666666,32.9625,43.461666666666666,31.253333333333334,87.9 +43.51111111111111,31.777777777777775,43.51111111111111,33.0,43.51111111111111,31.288888888888888,88.0 +43.56055555555555,31.813888888888886,43.56055555555555,33.0375,43.56055555555555,31.324444444444445,88.10000000000001 +43.61,31.849999999999998,43.61,33.074999999999996,43.61,31.36,88.2 +43.659444444444446,31.88611111111111,43.659444444444446,33.1125,43.659444444444446,31.395555555555557,88.30000000000001 +43.708888888888886,31.92222222222222,43.708888888888886,33.15,43.708888888888886,31.43111111111111,88.4 +43.75833333333333,31.95833333333333,43.75833333333333,33.1875,43.75833333333333,31.466666666666665,88.5 +43.80777777777778,31.99444444444444,43.80777777777778,33.225,43.80777777777778,31.502222222222223,88.60000000000001 +43.85722222222222,32.03055555555555,43.85722222222222,33.262499999999996,43.85722222222222,31.537777777777777,88.7 +43.906666666666666,32.06666666666666,43.906666666666666,33.3,43.906666666666666,31.573333333333334,88.80000000000001 +43.95611111111111,32.102777777777774,43.95611111111111,33.3375,43.95611111111111,31.608888888888888,88.9 +44.00555555555555,32.138888888888886,44.00555555555555,33.375,44.00555555555555,31.644444444444446,89.0 +44.055,32.175,44.055,33.4125,44.055,31.68,89.10000000000001 +44.10444444444445,32.21111111111111,44.10444444444445,33.449999999999996,44.10444444444445,31.715555555555557,89.2 +44.153888888888886,32.24722222222222,44.153888888888886,33.4875,44.153888888888886,31.75111111111111,89.30000000000001 +44.20333333333333,32.28333333333333,44.20333333333333,33.525,44.20333333333333,31.786666666666665,89.4 +44.25277777777778,32.31944444444444,44.25277777777778,33.5625,44.25277777777778,31.822222222222223,89.5 +44.30222222222222,32.355555555555554,44.30222222222222,33.6,44.30222222222222,31.857777777777777,89.60000000000001 +44.35166666666667,32.391666666666666,44.35166666666667,33.637499999999996,44.35166666666667,31.893333333333334,89.7 +44.40111111111111,32.42777777777778,44.40111111111111,33.675,44.40111111111111,31.92888888888889,89.80000000000001 +44.45055555555555,32.46388888888889,44.45055555555555,33.7125,44.45055555555555,31.964444444444446,89.9 +44.5,32.5,44.5,33.75,44.5,32.0,90.0 +44.54944444444445,32.53611111111111,44.54944444444445,33.7875,44.54944444444445,32.035555555555554,90.10000000000001 +44.59888888888889,32.572222222222216,44.59888888888889,33.824999999999996,44.59888888888889,32.07111111111111,90.2 +44.64833333333333,32.60833333333333,44.64833333333333,33.8625,44.64833333333333,32.10666666666667,90.30000000000001 +44.69777777777778,32.64444444444444,44.69777777777778,33.9,44.69777777777778,32.14222222222222,90.4 +44.74722222222222,32.68055555555555,44.74722222222222,33.9375,44.74722222222222,32.17777777777778,90.5 +44.79666666666667,32.71666666666666,44.79666666666667,33.975,44.79666666666667,32.21333333333333,90.60000000000001 +44.846111111111114,32.75277777777777,44.846111111111114,34.012499999999996,44.846111111111114,32.24888888888889,90.7 +44.89555555555555,32.788888888888884,44.89555555555555,34.05,44.89555555555555,32.284444444444446,90.80000000000001 +44.945,32.824999999999996,44.945,34.0875,44.945,32.32,90.9 +44.99444444444445,32.86111111111111,44.99444444444445,34.125,44.99444444444445,32.355555555555554,91.0 +45.04388888888889,32.89722222222222,45.04388888888889,34.1625,45.04388888888889,32.39111111111111,91.10000000000001 +45.093333333333334,32.93333333333333,45.093333333333334,34.199999999999996,45.093333333333334,32.42666666666667,91.2 +45.14277777777778,32.96944444444444,45.14277777777778,34.2375,45.14277777777778,32.46222222222222,91.30000000000001 +45.19222222222222,33.00555555555555,45.19222222222222,34.275,45.19222222222222,32.49777777777778,91.4 +45.24166666666667,33.041666666666664,45.24166666666667,34.3125,45.24166666666667,32.53333333333333,91.5 +45.29111111111111,33.077777777777776,45.29111111111111,34.35,45.29111111111111,32.568888888888885,91.60000000000001 +45.340555555555554,33.11388888888889,45.340555555555554,34.387499999999996,45.340555555555554,32.60444444444445,91.7 +45.39,33.15,45.39,34.425,45.39,32.64,91.80000000000001 +45.43944444444444,33.18611111111111,45.43944444444444,34.4625,45.43944444444444,32.675555555555555,91.9 +45.48888888888889,33.22222222222222,45.48888888888889,34.5,45.48888888888889,32.71111111111111,92.0 +45.538333333333334,33.25833333333333,45.538333333333334,34.5375,45.538333333333334,32.74666666666667,92.10000000000001 +45.587777777777774,33.294444444444444,45.587777777777774,34.574999999999996,45.587777777777774,32.782222222222224,92.2 +45.63722222222222,33.330555555555556,45.63722222222222,34.6125,45.63722222222222,32.81777777777778,92.30000000000001 +45.68666666666667,33.36666666666666,45.68666666666667,34.65,45.68666666666667,32.85333333333333,92.4 +45.73611111111111,33.40277777777777,45.73611111111111,34.6875,45.73611111111111,32.888888888888886,92.5 +45.785555555555554,33.43888888888888,45.785555555555554,34.725,45.785555555555554,32.92444444444445,92.60000000000001 +45.835,33.474999999999994,45.835,34.762499999999996,45.835,32.96,92.7 +45.88444444444444,33.511111111111106,45.88444444444444,34.8,45.88444444444444,32.995555555555555,92.80000000000001 +45.93388888888889,33.54722222222222,45.93388888888889,34.8375,45.93388888888889,33.03111111111111,92.9 +45.983333333333334,33.58333333333333,45.983333333333334,34.875,45.983333333333334,33.06666666666667,93.0 +46.032777777777774,33.61944444444444,46.032777777777774,34.9125,46.032777777777774,33.102222222222224,93.10000000000001 +46.08222222222222,33.65555555555555,46.08222222222222,34.949999999999996,46.08222222222222,33.13777777777778,93.2 +46.13166666666667,33.69166666666666,46.13166666666667,34.9875,46.13166666666667,33.17333333333333,93.30000000000001 +46.18111111111111,33.727777777777774,46.18111111111111,35.025,46.18111111111111,33.208888888888886,93.4 +46.230555555555554,33.763888888888886,46.230555555555554,35.0625,46.230555555555554,33.24444444444445,93.5 +46.28,33.8,46.28,35.1,46.28,33.28,93.60000000000001 +46.32944444444444,33.83611111111111,46.32944444444444,35.137499999999996,46.32944444444444,33.315555555555555,93.7 +46.37888888888889,33.87222222222222,46.37888888888889,35.175,46.37888888888889,33.35111111111111,93.80000000000001 +46.428333333333335,33.90833333333333,46.428333333333335,35.2125,46.428333333333335,33.38666666666666,93.9 +46.477777777777774,33.94444444444444,46.477777777777774,35.25,46.477777777777774,33.422222222222224,94.0 +46.52722222222222,33.980555555555554,46.52722222222222,35.2875,46.52722222222222,33.45777777777778,94.10000000000001 +46.57666666666667,34.016666666666666,46.57666666666667,35.324999999999996,46.57666666666667,33.49333333333333,94.2 +46.62611111111111,34.05277777777778,46.62611111111111,35.3625,46.62611111111111,33.528888888888886,94.30000000000001 +46.675555555555555,34.08888888888889,46.675555555555555,35.4,46.675555555555555,33.56444444444445,94.4 +46.725,34.125,46.725,35.4375,46.725,33.6,94.5 +46.77444444444444,34.16111111111111,46.77444444444444,35.475,46.77444444444444,33.635555555555555,94.60000000000001 +46.82388888888889,34.197222222222216,46.82388888888889,35.512499999999996,46.82388888888889,33.67111111111111,94.7 +46.873333333333335,34.23333333333333,46.873333333333335,35.55,46.873333333333335,33.70666666666666,94.80000000000001 +46.922777777777775,34.26944444444444,46.922777777777775,35.5875,46.922777777777775,33.742222222222225,94.9 +46.97222222222222,34.30555555555555,46.97222222222222,35.625,46.97222222222222,33.77777777777778,95.0 +47.02166666666667,34.34166666666666,47.02166666666667,35.6625,47.02166666666667,33.81333333333333,95.10000000000001 +47.07111111111111,34.37777777777777,47.07111111111111,35.699999999999996,47.07111111111111,33.84888888888889,95.2 +47.120555555555555,34.413888888888884,47.120555555555555,35.7375,47.120555555555555,33.88444444444445,95.30000000000001 +47.17,34.449999999999996,47.17,35.775,47.17,33.92,95.4 +47.21944444444444,34.48611111111111,47.21944444444444,35.8125,47.21944444444444,33.955555555555556,95.5 +47.26888888888889,34.52222222222222,47.26888888888889,35.85,47.26888888888889,33.99111111111111,95.60000000000001 +47.318333333333335,34.55833333333333,47.318333333333335,35.887499999999996,47.318333333333335,34.026666666666664,95.7 +47.367777777777775,34.59444444444444,47.367777777777775,35.925,47.367777777777775,34.062222222222225,95.80000000000001 +47.41722222222222,34.63055555555555,47.41722222222222,35.9625,47.41722222222222,34.09777777777778,95.9 +47.46666666666667,34.666666666666664,47.46666666666667,36.0,47.46666666666667,34.13333333333333,96.0 +47.51611111111111,34.702777777777776,47.51611111111111,36.0375,47.51611111111111,34.16888888888889,96.10000000000001 +47.565555555555555,34.73888888888889,47.565555555555555,36.074999999999996,47.565555555555555,34.20444444444444,96.2 +47.615,34.775,47.615,36.1125,47.615,34.24,96.30000000000001 +47.66444444444444,34.81111111111111,47.66444444444444,36.15,47.66444444444444,34.275555555555556,96.4 +47.71388888888889,34.84722222222222,47.71388888888889,36.1875,47.71388888888889,34.31111111111111,96.5 +47.763333333333335,34.88333333333333,47.763333333333335,36.225,47.763333333333335,34.346666666666664,96.60000000000001 +47.812777777777775,34.919444444444444,47.812777777777775,36.262499999999996,47.812777777777775,34.382222222222225,96.7 +47.86222222222222,34.955555555555556,47.86222222222222,36.3,47.86222222222222,34.41777777777778,96.80000000000001 +47.91166666666667,34.99166666666666,47.91166666666667,36.3375,47.91166666666667,34.45333333333333,96.9 +47.96111111111111,35.02777777777777,47.96111111111111,36.375,47.96111111111111,34.48888888888889,97.0 +48.010555555555555,35.06388888888888,48.010555555555555,36.4125,48.010555555555555,34.52444444444444,97.10000000000001 +48.06,35.099999999999994,48.06,36.449999999999996,48.06,34.56,97.2 +48.10944444444444,35.136111111111106,48.10944444444444,36.4875,48.10944444444444,34.595555555555556,97.30000000000001 +48.15888888888889,35.17222222222222,48.15888888888889,36.525,48.15888888888889,34.63111111111111,97.4 +48.208333333333336,35.20833333333333,48.208333333333336,36.5625,48.208333333333336,34.666666666666664,97.5 +48.257777777777775,35.24444444444444,48.257777777777775,36.6,48.257777777777775,34.702222222222225,97.60000000000001 +48.30722222222222,35.28055555555555,48.30722222222222,36.637499999999996,48.30722222222222,34.73777777777778,97.7 +48.35666666666667,35.31666666666666,48.35666666666667,36.675,48.35666666666667,34.77333333333333,97.80000000000001 +48.40611111111111,35.352777777777774,48.40611111111111,36.7125,48.40611111111111,34.80888888888889,97.9 +48.455555555555556,35.388888888888886,48.455555555555556,36.75,48.455555555555556,34.84444444444444,98.0 +48.505,35.425,48.505,36.7875,48.505,34.88,98.10000000000001 +48.55444444444444,35.46111111111111,48.55444444444444,36.824999999999996,48.55444444444444,34.91555555555556,98.2 +48.60388888888889,35.49722222222222,48.60388888888889,36.8625,48.60388888888889,34.95111111111111,98.30000000000001 +48.653333333333336,35.53333333333333,48.653333333333336,36.9,48.653333333333336,34.986666666666665,98.4 +48.702777777777776,35.56944444444444,48.702777777777776,36.9375,48.702777777777776,35.022222222222226,98.5 +48.75222222222222,35.605555555555554,48.75222222222222,36.975,48.75222222222222,35.05777777777778,98.60000000000001 +48.80166666666667,35.641666666666666,48.80166666666667,37.012499999999996,48.80166666666667,35.093333333333334,98.7 +48.85111111111111,35.67777777777778,48.85111111111111,37.05,48.85111111111111,35.12888888888889,98.80000000000001 +48.900555555555556,35.71388888888889,48.900555555555556,37.0875,48.900555555555556,35.16444444444444,98.9 +48.949999999999996,35.75,48.949999999999996,37.125,48.949999999999996,35.2,99.0 +48.99944444444444,35.786111111111104,48.99944444444444,37.1625,48.99944444444444,35.23555555555556,99.10000000000001 +49.04888888888889,35.822222222222216,49.04888888888889,37.199999999999996,49.04888888888889,35.27111111111111,99.2 +49.09833333333333,35.85833333333333,49.09833333333333,37.2375,49.09833333333333,35.306666666666665,99.30000000000001 +49.147777777777776,35.89444444444444,49.147777777777776,37.275,49.147777777777776,35.34222222222222,99.4 +49.19722222222222,35.93055555555555,49.19722222222222,37.3125,49.19722222222222,35.37777777777778,99.5 +49.24666666666666,35.96666666666666,49.24666666666666,37.35,49.24666666666666,35.413333333333334,99.60000000000001 +49.29611111111111,36.00277777777777,49.29611111111111,37.387499999999996,49.29611111111111,35.44888888888889,99.7 +49.345555555555556,36.038888888888884,49.345555555555556,37.425,49.345555555555556,35.48444444444444,99.80000000000001 +49.394999999999996,36.074999999999996,49.394999999999996,37.4625,49.394999999999996,35.52,99.9 +49.44444444444444,36.11111111111111,49.44444444444444,37.5,49.44444444444444,35.55555555555556,100.0 +49.49388888888889,36.14722222222222,49.49388888888889,37.5375,49.49388888888889,35.59111111111111,100.10000000000001 +49.54333333333333,36.18333333333333,49.54333333333333,37.574999999999996,49.54333333333333,35.626666666666665,100.2 +49.592777777777776,36.21944444444444,49.592777777777776,37.6125,49.592777777777776,35.66222222222222,100.30000000000001 +49.64222222222222,36.25555555555555,49.64222222222222,37.65,49.64222222222222,35.69777777777778,100.4 +49.69166666666666,36.291666666666664,49.69166666666666,37.6875,49.69166666666666,35.733333333333334,100.5 +49.74111111111111,36.327777777777776,49.74111111111111,37.725,49.74111111111111,35.76888888888889,100.60000000000001 +49.79055555555556,36.36388888888889,49.79055555555556,37.762499999999996,49.79055555555556,35.80444444444444,100.7 +49.839999999999996,36.4,49.839999999999996,37.8,49.839999999999996,35.84,100.80000000000001 +49.88944444444444,36.43611111111111,49.88944444444444,37.8375,49.88944444444444,35.87555555555556,100.9 +49.93888888888889,36.47222222222222,49.93888888888889,37.875,49.93888888888889,35.91111111111111,101.0 +49.98833333333333,36.50833333333333,49.98833333333333,37.9125,49.98833333333333,35.946666666666665,101.10000000000001 +50.03777777777778,36.544444444444444,50.03777777777778,37.949999999999996,50.03777777777778,35.98222222222222,101.2 +50.08722222222222,36.58055555555555,50.08722222222222,37.9875,50.08722222222222,36.01777777777778,101.30000000000001 +50.13666666666666,36.61666666666666,50.13666666666666,38.025,50.13666666666666,36.053333333333335,101.4 +50.18611111111111,36.65277777777777,50.18611111111111,38.0625,50.18611111111111,36.08888888888889,101.5 +50.23555555555556,36.68888888888888,50.23555555555556,38.1,50.23555555555556,36.12444444444444,101.60000000000001 +50.285,36.724999999999994,50.285,38.137499999999996,50.285,36.16,101.7 +50.33444444444444,36.761111111111106,50.33444444444444,38.175,50.33444444444444,36.19555555555556,101.80000000000001 +50.38388888888889,36.79722222222222,50.38388888888889,38.2125,50.38388888888889,36.23111111111111,101.9 +50.43333333333333,36.83333333333333,50.43333333333333,38.25,50.43333333333333,36.266666666666666,102.0 +50.48277777777778,36.86944444444444,50.48277777777778,38.2875,50.48277777777778,36.30222222222222,102.10000000000001 +50.532222222222224,36.90555555555555,50.532222222222224,38.324999999999996,50.532222222222224,36.33777777777778,102.2 +50.58166666666666,36.94166666666666,50.58166666666666,38.3625,50.58166666666666,36.373333333333335,102.30000000000001 +50.63111111111111,36.977777777777774,50.63111111111111,38.4,50.63111111111111,36.40888888888889,102.4 +50.68055555555556,37.013888888888886,50.68055555555556,38.4375,50.68055555555556,36.44444444444444,102.5 +50.73,37.05,50.73,38.475,50.73,36.48,102.60000000000001 +50.779444444444444,37.08611111111111,50.779444444444444,38.512499999999996,50.779444444444444,36.51555555555556,102.7 +50.82888888888889,37.12222222222222,50.82888888888889,38.55,50.82888888888889,36.55111111111111,102.80000000000001 +50.87833333333333,37.15833333333333,50.87833333333333,38.5875,50.87833333333333,36.586666666666666,102.9 +50.92777777777778,37.19444444444444,50.92777777777778,38.625,50.92777777777778,36.62222222222222,103.0 +50.977222222222224,37.230555555555554,50.977222222222224,38.6625,50.977222222222224,36.65777777777778,103.10000000000001 +51.026666666666664,37.266666666666666,51.026666666666664,38.699999999999996,51.026666666666664,36.693333333333335,103.2 +51.07611111111111,37.30277777777778,51.07611111111111,38.7375,51.07611111111111,36.72888888888889,103.30000000000001 +51.12555555555556,37.33888888888889,51.12555555555556,38.775,51.12555555555556,36.76444444444444,103.4 +51.175,37.375,51.175,38.8125,51.175,36.8,103.5 +51.224444444444444,37.411111111111104,51.224444444444444,38.85,51.224444444444444,36.83555555555556,103.60000000000001 +51.27388888888889,37.447222222222216,51.27388888888889,38.887499999999996,51.27388888888889,36.87111111111111,103.7 +51.32333333333333,37.48333333333333,51.32333333333333,38.925,51.32333333333333,36.906666666666666,103.80000000000001 +51.37277777777778,37.51944444444444,51.37277777777778,38.9625,51.37277777777778,36.94222222222222,103.9 +51.422222222222224,37.55555555555555,51.422222222222224,39.0,51.422222222222224,36.977777777777774,104.0 +51.471666666666664,37.59166666666666,51.471666666666664,39.0375,51.471666666666664,37.013333333333335,104.10000000000001 +51.52111111111111,37.62777777777777,51.52111111111111,39.074999999999996,51.52111111111111,37.04888888888889,104.2 +51.57055555555556,37.663888888888884,51.57055555555556,39.1125,51.57055555555556,37.08444444444444,104.30000000000001 +51.62,37.699999999999996,51.62,39.15,51.62,37.12,104.4 +51.669444444444444,37.73611111111111,51.669444444444444,39.1875,51.669444444444444,37.15555555555556,104.5 +51.71888888888889,37.77222222222222,51.71888888888889,39.225,51.71888888888889,37.19111111111111,104.60000000000001 +51.76833333333333,37.80833333333333,51.76833333333333,39.262499999999996,51.76833333333333,37.22666666666667,104.7 +51.81777777777778,37.84444444444444,51.81777777777778,39.3,51.81777777777778,37.26222222222222,104.80000000000001 +51.867222222222225,37.88055555555555,51.867222222222225,39.3375,51.867222222222225,37.297777777777775,104.9 +51.916666666666664,37.916666666666664,51.916666666666664,39.375,51.916666666666664,37.333333333333336,105.0 +51.96611111111111,37.952777777777776,51.96611111111111,39.4125,51.96611111111111,37.36888888888889,105.10000000000001 +52.01555555555556,37.98888888888889,52.01555555555556,39.449999999999996,52.01555555555556,37.404444444444444,105.2 +52.065,38.025,52.065,39.4875,52.065,37.44,105.30000000000001 +52.114444444444445,38.06111111111111,52.114444444444445,39.525,52.114444444444445,37.47555555555556,105.4 +52.16388888888889,38.09722222222222,52.16388888888889,39.5625,52.16388888888889,37.51111111111111,105.5 +52.21333333333333,38.13333333333333,52.21333333333333,39.6,52.21333333333333,37.54666666666667,105.60000000000001 +52.26277777777778,38.169444444444444,52.26277777777778,39.637499999999996,52.26277777777778,37.58222222222222,105.7 +52.312222222222225,38.20555555555555,52.312222222222225,39.675,52.312222222222225,37.617777777777775,105.80000000000001 +52.361666666666665,38.24166666666666,52.361666666666665,39.7125,52.361666666666665,37.653333333333336,105.9 +52.41111111111111,38.27777777777777,52.41111111111111,39.75,52.41111111111111,37.68888888888889,106.0 +52.46055555555555,38.31388888888888,52.46055555555555,39.7875,52.46055555555555,37.724444444444444,106.10000000000001 +52.51,38.349999999999994,52.51,39.824999999999996,52.51,37.76,106.2 +52.559444444444445,38.386111111111106,52.559444444444445,39.8625,52.559444444444445,37.79555555555555,106.30000000000001 +52.608888888888885,38.42222222222222,52.608888888888885,39.9,52.608888888888885,37.83111111111111,106.4 +52.65833333333333,38.45833333333333,52.65833333333333,39.9375,52.65833333333333,37.86666666666667,106.5 +52.70777777777778,38.49444444444444,52.70777777777778,39.975,52.70777777777778,37.90222222222222,106.60000000000001 +52.75722222222222,38.53055555555555,52.75722222222222,40.012499999999996,52.75722222222222,37.937777777777775,106.7 +52.806666666666665,38.56666666666666,52.806666666666665,40.05,52.806666666666665,37.973333333333336,106.80000000000001 +52.85611111111111,38.602777777777774,52.85611111111111,40.0875,52.85611111111111,38.00888888888889,106.9 +52.90555555555555,38.638888888888886,52.90555555555555,40.125,52.90555555555555,38.044444444444444,107.0 +52.955,38.675,52.955,40.1625,52.955,38.08,107.10000000000001 +53.004444444444445,38.71111111111111,53.004444444444445,40.199999999999996,53.004444444444445,38.11555555555555,107.2 +53.053888888888885,38.74722222222222,53.053888888888885,40.2375,53.053888888888885,38.15111111111111,107.30000000000001 +53.10333333333333,38.78333333333333,53.10333333333333,40.275,53.10333333333333,38.18666666666667,107.4 +53.15277777777778,38.81944444444444,53.15277777777778,40.3125,53.15277777777778,38.22222222222222,107.5 +53.20222222222222,38.855555555555554,53.20222222222222,40.35,53.20222222222222,38.257777777777775,107.60000000000001 +53.251666666666665,38.891666666666666,53.251666666666665,40.387499999999996,53.251666666666665,38.29333333333334,107.7 +53.30111111111111,38.92777777777778,53.30111111111111,40.425,53.30111111111111,38.32888888888889,107.80000000000001 +53.35055555555555,38.96388888888889,53.35055555555555,40.4625,53.35055555555555,38.364444444444445,107.9 +53.4,38.99999999999999,53.4,40.5,53.4,38.4,108.0 +53.449444444444445,39.036111111111104,53.449444444444445,40.5375,53.449444444444445,38.43555555555555,108.10000000000001 +53.498888888888885,39.072222222222216,53.498888888888885,40.574999999999996,53.498888888888885,38.471111111111114,108.2 +53.54833333333333,39.10833333333333,53.54833333333333,40.6125,53.54833333333333,38.50666666666667,108.30000000000001 +53.59777777777778,39.14444444444444,53.59777777777778,40.65,53.59777777777778,38.54222222222222,108.4 +53.64722222222222,39.18055555555555,53.64722222222222,40.6875,53.64722222222222,38.577777777777776,108.5 +53.696666666666665,39.21666666666666,53.696666666666665,40.725,53.696666666666665,38.61333333333334,108.60000000000001 +53.74611111111111,39.25277777777777,53.74611111111111,40.762499999999996,53.74611111111111,38.64888888888889,108.7 +53.79555555555555,39.288888888888884,53.79555555555555,40.8,53.79555555555555,38.684444444444445,108.80000000000001 +53.845,39.324999999999996,53.845,40.8375,53.845,38.72,108.9 +53.894444444444446,39.36111111111111,53.894444444444446,40.875,53.894444444444446,38.75555555555555,109.0 +53.943888888888885,39.39722222222222,53.943888888888885,40.9125,53.943888888888885,38.791111111111114,109.10000000000001 +53.99333333333333,39.43333333333333,53.99333333333333,40.949999999999996,53.99333333333333,38.82666666666667,109.2 +54.04277777777778,39.46944444444444,54.04277777777778,40.9875,54.04277777777778,38.86222222222222,109.30000000000001 +54.09222222222222,39.50555555555555,54.09222222222222,41.025,54.09222222222222,38.897777777777776,109.4 +54.141666666666666,39.541666666666664,54.141666666666666,41.0625,54.141666666666666,38.93333333333333,109.5 +54.19111111111111,39.577777777777776,54.19111111111111,41.1,54.19111111111111,38.96888888888889,109.60000000000001 +54.24055555555555,39.61388888888889,54.24055555555555,41.137499999999996,54.24055555555555,39.004444444444445,109.7 +54.29,39.65,54.29,41.175,54.29,39.04,109.80000000000001 +54.339444444444446,39.68611111111111,54.339444444444446,41.2125,54.339444444444446,39.07555555555555,109.9 +54.388888888888886,39.72222222222222,54.388888888888886,41.25,54.388888888888886,39.111111111111114,110.0 +54.43833333333333,39.75833333333333,54.43833333333333,41.2875,54.43833333333333,39.14666666666667,110.10000000000001 +54.48777777777778,39.79444444444444,54.48777777777778,41.324999999999996,54.48777777777778,39.18222222222222,110.2 +54.53722222222222,39.83055555555555,54.53722222222222,41.3625,54.53722222222222,39.217777777777776,110.30000000000001 +54.586666666666666,39.86666666666666,54.586666666666666,41.4,54.586666666666666,39.25333333333333,110.4 +54.63611111111111,39.90277777777777,54.63611111111111,41.4375,54.63611111111111,39.28888888888889,110.5 +54.68555555555555,39.93888888888888,54.68555555555555,41.475,54.68555555555555,39.324444444444445,110.60000000000001 +54.735,39.974999999999994,54.735,41.512499999999996,54.735,39.36,110.7 +54.784444444444446,40.011111111111106,54.784444444444446,41.55,54.784444444444446,39.39555555555555,110.80000000000001 +54.833888888888886,40.04722222222222,54.833888888888886,41.5875,54.833888888888886,39.431111111111115,110.9 +54.88333333333333,40.08333333333333,54.88333333333333,41.625,54.88333333333333,39.46666666666667,111.0 +54.93277777777778,40.11944444444444,54.93277777777778,41.6625,54.93277777777778,39.50222222222222,111.10000000000001 +54.98222222222222,40.15555555555555,54.98222222222222,41.699999999999996,54.98222222222222,39.53777777777778,111.2 +55.031666666666666,40.19166666666666,55.031666666666666,41.7375,55.031666666666666,39.57333333333333,111.30000000000001 +55.08111111111111,40.227777777777774,55.08111111111111,41.775,55.08111111111111,39.60888888888889,111.4 +55.13055555555555,40.263888888888886,55.13055555555555,41.8125,55.13055555555555,39.644444444444446,111.5 +55.18,40.3,55.18,41.85,55.18,39.68,111.60000000000001 +55.22944444444445,40.33611111111111,55.22944444444445,41.887499999999996,55.22944444444445,39.715555555555554,111.7 +55.278888888888886,40.37222222222222,55.278888888888886,41.925,55.278888888888886,39.75111111111111,111.80000000000001 +55.32833333333333,40.40833333333333,55.32833333333333,41.9625,55.32833333333333,39.78666666666667,111.9 +55.37777777777778,40.44444444444444,55.37777777777778,42.0,55.37777777777778,39.82222222222222,112.0 +55.42722222222222,40.480555555555554,55.42722222222222,42.0375,55.42722222222222,39.85777777777778,112.10000000000001 +55.47666666666667,40.516666666666666,55.47666666666667,42.074999999999996,55.47666666666667,39.89333333333333,112.2 +55.52611111111111,40.55277777777778,55.52611111111111,42.1125,55.52611111111111,39.92888888888889,112.30000000000001 +55.57555555555555,40.58888888888889,55.57555555555555,42.15,55.57555555555555,39.964444444444446,112.4 +55.625,40.62499999999999,55.625,42.1875,55.625,40.0,112.5 +55.67444444444445,40.661111111111104,55.67444444444445,42.225,55.67444444444445,40.035555555555554,112.60000000000001 +55.72388888888889,40.697222222222216,55.72388888888889,42.262499999999996,55.72388888888889,40.07111111111111,112.7 +55.77333333333333,40.73333333333333,55.77333333333333,42.3,55.77333333333333,40.10666666666667,112.80000000000001 +55.82277777777778,40.76944444444444,55.82277777777778,42.3375,55.82277777777778,40.14222222222222,112.9 +55.87222222222222,40.80555555555555,55.87222222222222,42.375,55.87222222222222,40.17777777777778,113.0 +55.92166666666667,40.84166666666666,55.92166666666667,42.4125,55.92166666666667,40.21333333333333,113.10000000000001 +55.971111111111114,40.87777777777777,55.971111111111114,42.449999999999996,55.971111111111114,40.24888888888889,113.2 +56.02055555555555,40.913888888888884,56.02055555555555,42.4875,56.02055555555555,40.284444444444446,113.30000000000001 +56.07,40.949999999999996,56.07,42.525,56.07,40.32,113.4 +56.11944444444444,40.98611111111111,56.11944444444444,42.5625,56.11944444444444,40.355555555555554,113.5 +56.16888888888889,41.02222222222222,56.16888888888889,42.6,56.16888888888889,40.39111111111111,113.60000000000001 +56.218333333333334,41.05833333333333,56.218333333333334,42.637499999999996,56.218333333333334,40.42666666666667,113.7 +56.26777777777777,41.09444444444444,56.26777777777777,42.675,56.26777777777777,40.46222222222222,113.80000000000001 +56.31722222222222,41.13055555555555,56.31722222222222,42.7125,56.31722222222222,40.49777777777778,113.9 +56.36666666666667,41.166666666666664,56.36666666666667,42.75,56.36666666666667,40.53333333333333,114.0 +56.41611111111111,41.202777777777776,56.41611111111111,42.7875,56.41611111111111,40.568888888888885,114.10000000000001 +56.465555555555554,41.23888888888889,56.465555555555554,42.824999999999996,56.465555555555554,40.60444444444445,114.2 +56.515,41.275,56.515,42.8625,56.515,40.64,114.30000000000001 +56.56444444444444,41.31111111111111,56.56444444444444,42.9,56.56444444444444,40.675555555555555,114.4 +56.61388888888889,41.34722222222222,56.61388888888889,42.9375,56.61388888888889,40.71111111111111,114.5 +56.663333333333334,41.38333333333333,56.663333333333334,42.975,56.663333333333334,40.74666666666667,114.60000000000001 +56.712777777777774,41.41944444444444,56.712777777777774,43.012499999999996,56.712777777777774,40.782222222222224,114.7 +56.76222222222222,41.45555555555555,56.76222222222222,43.05,56.76222222222222,40.81777777777778,114.80000000000001 +56.81166666666667,41.49166666666666,56.81166666666667,43.0875,56.81166666666667,40.85333333333333,114.9 +56.86111111111111,41.52777777777777,56.86111111111111,43.125,56.86111111111111,40.888888888888886,115.0 +56.910555555555554,41.56388888888888,56.910555555555554,43.1625,56.910555555555554,40.92444444444445,115.10000000000001 +56.96,41.599999999999994,56.96,43.199999999999996,56.96,40.96,115.2 +57.00944444444444,41.636111111111106,57.00944444444444,43.2375,57.00944444444444,40.995555555555555,115.30000000000001 +57.05888888888889,41.67222222222222,57.05888888888889,43.275,57.05888888888889,41.03111111111111,115.4 +57.108333333333334,41.70833333333333,57.108333333333334,43.3125,57.108333333333334,41.06666666666667,115.5 +57.157777777777774,41.74444444444444,57.157777777777774,43.35,57.157777777777774,41.102222222222224,115.60000000000001 +57.20722222222222,41.78055555555555,57.20722222222222,43.387499999999996,57.20722222222222,41.13777777777778,115.7 +57.25666666666667,41.81666666666666,57.25666666666667,43.425,57.25666666666667,41.17333333333333,115.80000000000001 +57.30611111111111,41.852777777777774,57.30611111111111,43.4625,57.30611111111111,41.208888888888886,115.9 +57.355555555555554,41.888888888888886,57.355555555555554,43.5,57.355555555555554,41.24444444444445,116.0 +57.405,41.925,57.405,43.5375,57.405,41.28,116.10000000000001 +57.45444444444444,41.96111111111111,57.45444444444444,43.574999999999996,57.45444444444444,41.315555555555555,116.2 +57.50388888888889,41.99722222222222,57.50388888888889,43.6125,57.50388888888889,41.35111111111111,116.30000000000001 +57.553333333333335,42.03333333333333,57.553333333333335,43.65,57.553333333333335,41.38666666666666,116.4 +57.602777777777774,42.06944444444444,57.602777777777774,43.6875,57.602777777777774,41.422222222222224,116.5 +57.65222222222222,42.105555555555554,57.65222222222222,43.725,57.65222222222222,41.45777777777778,116.60000000000001 +57.70166666666667,42.141666666666666,57.70166666666667,43.762499999999996,57.70166666666667,41.49333333333333,116.7 +57.75111111111111,42.17777777777778,57.75111111111111,43.8,57.75111111111111,41.528888888888886,116.80000000000001 +57.800555555555555,42.21388888888888,57.800555555555555,43.8375,57.800555555555555,41.56444444444445,116.9 +57.85,42.24999999999999,57.85,43.875,57.85,41.6,117.0 +57.89944444444444,42.286111111111104,57.89944444444444,43.9125,57.89944444444444,41.635555555555555,117.10000000000001 +57.94888888888889,42.322222222222216,57.94888888888889,43.949999999999996,57.94888888888889,41.67111111111111,117.2 +57.998333333333335,42.35833333333333,57.998333333333335,43.9875,57.998333333333335,41.70666666666666,117.30000000000001 +58.047777777777775,42.39444444444444,58.047777777777775,44.025,58.047777777777775,41.742222222222225,117.4 +58.09722222222222,42.43055555555555,58.09722222222222,44.0625,58.09722222222222,41.77777777777778,117.5 +58.14666666666667,42.46666666666666,58.14666666666667,44.1,58.14666666666667,41.81333333333333,117.60000000000001 +58.19611111111111,42.50277777777777,58.19611111111111,44.137499999999996,58.19611111111111,41.84888888888889,117.7 +58.245555555555555,42.538888888888884,58.245555555555555,44.175,58.245555555555555,41.88444444444445,117.80000000000001 +58.295,42.574999999999996,58.295,44.2125,58.295,41.92,117.9 +58.34444444444444,42.61111111111111,58.34444444444444,44.25,58.34444444444444,41.955555555555556,118.0 +58.39388888888889,42.64722222222222,58.39388888888889,44.2875,58.39388888888889,41.99111111111111,118.10000000000001 +58.443333333333335,42.68333333333333,58.443333333333335,44.324999999999996,58.443333333333335,42.026666666666664,118.2 +58.492777777777775,42.71944444444444,58.492777777777775,44.3625,58.492777777777775,42.062222222222225,118.30000000000001 +58.54222222222222,42.75555555555555,58.54222222222222,44.4,58.54222222222222,42.09777777777778,118.4 +58.59166666666667,42.791666666666664,58.59166666666667,44.4375,58.59166666666667,42.13333333333333,118.5 +58.64111111111111,42.827777777777776,58.64111111111111,44.475,58.64111111111111,42.16888888888889,118.60000000000001 +58.690555555555555,42.86388888888889,58.690555555555555,44.512499999999996,58.690555555555555,42.20444444444444,118.7 +58.74,42.9,58.74,44.55,58.74,42.24,118.80000000000001 +58.78944444444444,42.93611111111111,58.78944444444444,44.5875,58.78944444444444,42.275555555555556,118.9 +58.83888888888889,42.97222222222222,58.83888888888889,44.625,58.83888888888889,42.31111111111111,119.0 +58.888333333333335,43.008333333333326,58.888333333333335,44.6625,58.888333333333335,42.346666666666664,119.10000000000001 +58.937777777777775,43.04444444444444,58.937777777777775,44.699999999999996,58.937777777777775,42.382222222222225,119.2 +58.98722222222222,43.08055555555555,58.98722222222222,44.7375,58.98722222222222,42.41777777777778,119.30000000000001 +59.03666666666667,43.11666666666666,59.03666666666667,44.775,59.03666666666667,42.45333333333333,119.4 +59.08611111111111,43.15277777777777,59.08611111111111,44.8125,59.08611111111111,42.48888888888889,119.5 +59.135555555555555,43.18888888888888,59.135555555555555,44.85,59.135555555555555,42.52444444444444,119.60000000000001 +59.185,43.224999999999994,59.185,44.887499999999996,59.185,42.56,119.7 +59.23444444444444,43.261111111111106,59.23444444444444,44.925,59.23444444444444,42.595555555555556,119.80000000000001 +59.28388888888889,43.29722222222222,59.28388888888889,44.9625,59.28388888888889,42.63111111111111,119.9 +59.333333333333336,43.33333333333333,59.333333333333336,45.0,59.333333333333336,42.666666666666664,120.0 +59.382777777777775,43.36944444444444,59.382777777777775,45.0375,59.382777777777775,42.702222222222225,120.10000000000001 +59.43222222222222,43.40555555555555,59.43222222222222,45.074999999999996,59.43222222222222,42.73777777777778,120.2 +59.48166666666667,43.44166666666666,59.48166666666667,45.1125,59.48166666666667,42.77333333333333,120.30000000000001 +59.53111111111111,43.477777777777774,59.53111111111111,45.15,59.53111111111111,42.80888888888889,120.4 +59.580555555555556,43.513888888888886,59.580555555555556,45.1875,59.580555555555556,42.84444444444444,120.5 +59.63,43.55,59.63,45.225,59.63,42.88,120.60000000000001 +59.67944444444444,43.58611111111111,59.67944444444444,45.262499999999996,59.67944444444444,42.91555555555556,120.7 +59.72888888888889,43.62222222222222,59.72888888888889,45.3,59.72888888888889,42.95111111111111,120.80000000000001 +59.77833333333333,43.65833333333333,59.77833333333333,45.3375,59.77833333333333,42.986666666666665,120.9 +59.827777777777776,43.69444444444444,59.827777777777776,45.375,59.827777777777776,43.022222222222226,121.0 +59.87722222222222,43.730555555555554,59.87722222222222,45.4125,59.87722222222222,43.05777777777778,121.10000000000001 +59.92666666666666,43.766666666666666,59.92666666666666,45.449999999999996,59.92666666666666,43.093333333333334,121.2 +59.97611111111111,43.80277777777778,59.97611111111111,45.4875,59.97611111111111,43.12888888888889,121.30000000000001 +60.025555555555556,43.83888888888888,60.025555555555556,45.525,60.025555555555556,43.16444444444444,121.4 +60.074999999999996,43.87499999999999,60.074999999999996,45.5625,60.074999999999996,43.2,121.5 +60.12444444444444,43.911111111111104,60.12444444444444,45.6,60.12444444444444,43.23555555555556,121.60000000000001 +60.17388888888889,43.947222222222216,60.17388888888889,45.637499999999996,60.17388888888889,43.27111111111111,121.7 +60.22333333333333,43.98333333333333,60.22333333333333,45.675,60.22333333333333,43.306666666666665,121.80000000000001 +60.272777777777776,44.01944444444444,60.272777777777776,45.7125,60.272777777777776,43.34222222222222,121.9 +60.32222222222222,44.05555555555555,60.32222222222222,45.75,60.32222222222222,43.37777777777778,122.0 +60.37166666666666,44.09166666666666,60.37166666666666,45.7875,60.37166666666666,43.413333333333334,122.10000000000001 +60.42111111111111,44.12777777777777,60.42111111111111,45.824999999999996,60.42111111111111,43.44888888888889,122.2 +60.470555555555556,44.163888888888884,60.470555555555556,45.8625,60.470555555555556,43.48444444444444,122.30000000000001 +60.519999999999996,44.199999999999996,60.519999999999996,45.9,60.519999999999996,43.52,122.4 +60.56944444444444,44.23611111111111,60.56944444444444,45.9375,60.56944444444444,43.55555555555556,122.5 +60.61888888888889,44.27222222222222,60.61888888888889,45.975,60.61888888888889,43.59111111111111,122.60000000000001 +60.66833333333333,44.30833333333333,60.66833333333333,46.012499999999996,60.66833333333333,43.626666666666665,122.7 +60.717777777777776,44.34444444444444,60.717777777777776,46.05,60.717777777777776,43.66222222222222,122.80000000000001 +60.76722222222222,44.38055555555555,60.76722222222222,46.0875,60.76722222222222,43.69777777777778,122.9 +60.81666666666666,44.416666666666664,60.81666666666666,46.125,60.81666666666666,43.733333333333334,123.0 +60.86611111111111,44.452777777777776,60.86611111111111,46.1625,60.86611111111111,43.76888888888889,123.10000000000001 +60.91555555555556,44.48888888888889,60.91555555555556,46.199999999999996,60.91555555555556,43.80444444444444,123.2 +60.964999999999996,44.525,60.964999999999996,46.2375,60.964999999999996,43.84,123.30000000000001 +61.01444444444444,44.56111111111111,61.01444444444444,46.275,61.01444444444444,43.87555555555556,123.4 +61.06388888888889,44.59722222222222,61.06388888888889,46.3125,61.06388888888889,43.91111111111111,123.5 +61.11333333333333,44.633333333333326,61.11333333333333,46.35,61.11333333333333,43.946666666666665,123.60000000000001 +61.16277777777778,44.66944444444444,61.16277777777778,46.387499999999996,61.16277777777778,43.98222222222222,123.7 +61.21222222222222,44.70555555555555,61.21222222222222,46.425,61.21222222222222,44.01777777777778,123.80000000000001 +61.26166666666666,44.74166666666666,61.26166666666666,46.4625,61.26166666666666,44.053333333333335,123.9 +61.31111111111111,44.77777777777777,61.31111111111111,46.5,61.31111111111111,44.08888888888889,124.0 +61.36055555555556,44.81388888888888,61.36055555555556,46.5375,61.36055555555556,44.12444444444444,124.10000000000001 +61.41,44.849999999999994,61.41,46.574999999999996,61.41,44.16,124.2 +61.45944444444444,44.886111111111106,61.45944444444444,46.6125,61.45944444444444,44.19555555555556,124.30000000000001 +61.50888888888889,44.92222222222222,61.50888888888889,46.65,61.50888888888889,44.23111111111111,124.4 +61.55833333333333,44.95833333333333,61.55833333333333,46.6875,61.55833333333333,44.266666666666666,124.5 +61.60777777777778,44.99444444444444,61.60777777777778,46.725,61.60777777777778,44.30222222222222,124.60000000000001 +61.657222222222224,45.03055555555555,61.657222222222224,46.762499999999996,61.657222222222224,44.33777777777778,124.7 +61.70666666666666,45.06666666666666,61.70666666666666,46.8,61.70666666666666,44.373333333333335,124.80000000000001 +61.75611111111111,45.102777777777774,61.75611111111111,46.8375,61.75611111111111,44.40888888888889,124.9 +61.80555555555556,45.138888888888886,61.80555555555556,46.875,61.80555555555556,44.44444444444444,125.0 +61.855,45.175,61.855,46.9125,61.855,44.48,125.10000000000001 +61.904444444444444,45.21111111111111,61.904444444444444,46.949999999999996,61.904444444444444,44.51555555555556,125.2 +61.95388888888889,45.24722222222222,61.95388888888889,46.9875,61.95388888888889,44.55111111111111,125.30000000000001 +62.00333333333333,45.28333333333333,62.00333333333333,47.025,62.00333333333333,44.586666666666666,125.4 +62.05277777777778,45.31944444444444,62.05277777777778,47.0625,62.05277777777778,44.62222222222222,125.5 +62.102222222222224,45.355555555555554,62.102222222222224,47.1,62.102222222222224,44.65777777777778,125.60000000000001 +62.151666666666664,45.391666666666666,62.151666666666664,47.137499999999996,62.151666666666664,44.693333333333335,125.7 +62.20111111111111,45.42777777777777,62.20111111111111,47.175,62.20111111111111,44.72888888888889,125.80000000000001 +62.25055555555556,45.46388888888888,62.25055555555556,47.2125,62.25055555555556,44.76444444444444,125.9 +62.3,45.49999999999999,62.3,47.25,62.3,44.8,126.0 +62.349444444444444,45.536111111111104,62.349444444444444,47.2875,62.349444444444444,44.83555555555556,126.10000000000001 +62.39888888888889,45.572222222222216,62.39888888888889,47.324999999999996,62.39888888888889,44.87111111111111,126.2 +62.44833333333333,45.60833333333333,62.44833333333333,47.3625,62.44833333333333,44.906666666666666,126.30000000000001 +62.49777777777778,45.64444444444444,62.49777777777778,47.4,62.49777777777778,44.94222222222222,126.4 +62.547222222222224,45.68055555555555,62.547222222222224,47.4375,62.547222222222224,44.977777777777774,126.5 +62.596666666666664,45.71666666666666,62.596666666666664,47.475,62.596666666666664,45.013333333333335,126.60000000000001 +62.64611111111111,45.75277777777777,62.64611111111111,47.512499999999996,62.64611111111111,45.04888888888889,126.7 +62.69555555555556,45.788888888888884,62.69555555555556,47.55,62.69555555555556,45.08444444444444,126.80000000000001 +62.745,45.824999999999996,62.745,47.5875,62.745,45.12,126.9 +62.794444444444444,45.86111111111111,62.794444444444444,47.625,62.794444444444444,45.15555555555556,127.0 +62.84388888888889,45.89722222222222,62.84388888888889,47.6625,62.84388888888889,45.19111111111111,127.10000000000001 +62.89333333333333,45.93333333333333,62.89333333333333,47.699999999999996,62.89333333333333,45.22666666666667,127.2 +62.94277777777778,45.96944444444444,62.94277777777778,47.7375,62.94277777777778,45.26222222222222,127.30000000000001 +62.992222222222225,46.00555555555555,62.992222222222225,47.775,62.992222222222225,45.297777777777775,127.4 +63.041666666666664,46.041666666666664,63.041666666666664,47.8125,63.041666666666664,45.333333333333336,127.5 +63.09111111111111,46.077777777777776,63.09111111111111,47.85,63.09111111111111,45.36888888888889,127.60000000000001 +63.14055555555556,46.11388888888889,63.14055555555556,47.887499999999996,63.14055555555556,45.404444444444444,127.7 +63.19,46.15,63.19,47.925,63.19,45.44,127.80000000000001 +63.239444444444445,46.18611111111111,63.239444444444445,47.9625,63.239444444444445,45.47555555555556,127.9 +63.28888888888889,46.222222222222214,63.28888888888889,48.0,63.28888888888889,45.51111111111111,128.0 +63.33833333333333,46.258333333333326,63.33833333333333,48.0375,63.33833333333333,45.54666666666667,128.1 +63.38777777777778,46.29444444444444,63.38777777777778,48.074999999999996,63.38777777777778,45.58222222222222,128.20000000000002 +63.43722222222222,46.33055555555555,63.43722222222222,48.1125,63.43722222222222,45.617777777777775,128.3 +63.486666666666665,46.36666666666666,63.486666666666665,48.15,63.486666666666665,45.653333333333336,128.4 +63.53611111111111,46.40277777777777,63.53611111111111,48.1875,63.53611111111111,45.68888888888889,128.5 +63.58555555555555,46.43888888888888,63.58555555555555,48.225,63.58555555555555,45.724444444444444,128.6 +63.635,46.474999999999994,63.635,48.262499999999996,63.635,45.76,128.70000000000002 +63.684444444444445,46.511111111111106,63.684444444444445,48.3,63.684444444444445,45.79555555555555,128.8 +63.733888888888885,46.54722222222222,63.733888888888885,48.3375,63.733888888888885,45.83111111111111,128.9 +63.78333333333333,46.58333333333333,63.78333333333333,48.375,63.78333333333333,45.86666666666667,129.0 +63.83277777777778,46.61944444444444,63.83277777777778,48.4125,63.83277777777778,45.90222222222222,129.1 +63.88222222222222,46.65555555555555,63.88222222222222,48.449999999999996,63.88222222222222,45.937777777777775,129.20000000000002 +63.931666666666665,46.69166666666666,63.931666666666665,48.4875,63.931666666666665,45.973333333333336,129.3 +63.98111111111111,46.727777777777774,63.98111111111111,48.525,63.98111111111111,46.00888888888889,129.4 +64.03055555555555,46.763888888888886,64.03055555555555,48.5625,64.03055555555555,46.044444444444444,129.5 +64.08,46.8,64.08,48.6,64.08,46.08,129.6 +64.12944444444445,46.83611111111111,64.12944444444445,48.637499999999996,64.12944444444445,46.11555555555555,129.70000000000002 +64.17888888888889,46.87222222222222,64.17888888888889,48.675,64.17888888888889,46.15111111111111,129.8 +64.22833333333334,46.90833333333333,64.22833333333334,48.7125,64.22833333333334,46.18666666666667,129.9 +64.27777777777777,46.94444444444444,64.27777777777777,48.75,64.27777777777777,46.22222222222222,130.0 +64.32722222222222,46.980555555555554,64.32722222222222,48.7875,64.32722222222222,46.257777777777775,130.1 +64.37666666666667,47.016666666666666,64.37666666666667,48.824999999999996,64.37666666666667,46.29333333333334,130.20000000000002 +64.42611111111111,47.05277777777777,64.42611111111111,48.8625,64.42611111111111,46.32888888888889,130.3 +64.47555555555556,47.08888888888888,64.47555555555556,48.9,64.47555555555556,46.364444444444445,130.4 +64.525,47.12499999999999,64.525,48.9375,64.525,46.4,130.5 +64.57444444444444,47.161111111111104,64.57444444444444,48.975,64.57444444444444,46.43555555555555,130.6 +64.62388888888889,47.197222222222216,64.62388888888889,49.012499999999996,64.62388888888889,46.471111111111114,130.70000000000002 +64.67333333333333,47.23333333333333,64.67333333333333,49.05,64.67333333333333,46.50666666666667,130.8 +64.72277777777778,47.26944444444444,64.72277777777778,49.0875,64.72277777777778,46.54222222222222,130.9 +64.77222222222223,47.30555555555555,64.77222222222223,49.125,64.77222222222223,46.577777777777776,131.0 +64.82166666666667,47.34166666666666,64.82166666666667,49.1625,64.82166666666667,46.61333333333334,131.1 +64.8711111111111,47.37777777777777,64.8711111111111,49.199999999999996,64.8711111111111,46.64888888888889,131.20000000000002 +64.92055555555555,47.413888888888884,64.92055555555555,49.2375,64.92055555555555,46.684444444444445,131.3 +64.97,47.449999999999996,64.97,49.275,64.97,46.72,131.4 +65.01944444444445,47.48611111111111,65.01944444444445,49.3125,65.01944444444445,46.75555555555555,131.5 +65.06888888888889,47.52222222222222,65.06888888888889,49.35,65.06888888888889,46.791111111111114,131.6 +65.11833333333333,47.55833333333333,65.11833333333333,49.387499999999996,65.11833333333333,46.82666666666667,131.70000000000002 +65.16777777777777,47.59444444444444,65.16777777777777,49.425,65.16777777777777,46.86222222222222,131.8 +65.21722222222222,47.63055555555555,65.21722222222222,49.4625,65.21722222222222,46.897777777777776,131.9 +65.26666666666667,47.666666666666664,65.26666666666667,49.5,65.26666666666667,46.93333333333333,132.0 +65.31611111111111,47.702777777777776,65.31611111111111,49.5375,65.31611111111111,46.96888888888889,132.1 +65.36555555555556,47.73888888888889,65.36555555555556,49.574999999999996,65.36555555555556,47.004444444444445,132.20000000000002 +65.41499999999999,47.775,65.41499999999999,49.6125,65.41499999999999,47.04,132.3 +65.46444444444444,47.81111111111111,65.46444444444444,49.65,65.46444444444444,47.07555555555555,132.4 +65.51388888888889,47.847222222222214,65.51388888888889,49.6875,65.51388888888889,47.111111111111114,132.5 +65.56333333333333,47.883333333333326,65.56333333333333,49.725,65.56333333333333,47.14666666666667,132.6 +65.61277777777778,47.91944444444444,65.61277777777778,49.762499999999996,65.61277777777778,47.18222222222222,132.70000000000002 +65.66222222222223,47.95555555555555,65.66222222222223,49.8,65.66222222222223,47.217777777777776,132.8 +65.71166666666666,47.99166666666666,65.71166666666666,49.8375,65.71166666666666,47.25333333333333,132.9 +65.7611111111111,48.02777777777777,65.7611111111111,49.875,65.7611111111111,47.28888888888889,133.0 +65.81055555555555,48.06388888888888,65.81055555555555,49.9125,65.81055555555555,47.324444444444445,133.1 +65.86,48.099999999999994,65.86,49.949999999999996,65.86,47.36,133.20000000000002 +65.90944444444445,48.136111111111106,65.90944444444445,49.9875,65.90944444444445,47.39555555555555,133.3 +65.9588888888889,48.17222222222222,65.9588888888889,50.025,65.9588888888889,47.431111111111115,133.4 +66.00833333333333,48.20833333333333,66.00833333333333,50.0625,66.00833333333333,47.46666666666667,133.5 +66.05777777777777,48.24444444444444,66.05777777777777,50.1,66.05777777777777,47.50222222222222,133.6 +66.10722222222222,48.28055555555555,66.10722222222222,50.137499999999996,66.10722222222222,47.53777777777778,133.70000000000002 +66.15666666666667,48.31666666666666,66.15666666666667,50.175,66.15666666666667,47.57333333333333,133.8 +66.20611111111111,48.352777777777774,66.20611111111111,50.2125,66.20611111111111,47.60888888888889,133.9 +66.25555555555556,48.388888888888886,66.25555555555556,50.25,66.25555555555556,47.644444444444446,134.0 +66.30499999999999,48.425,66.30499999999999,50.2875,66.30499999999999,47.68,134.1 +66.35444444444444,48.46111111111111,66.35444444444444,50.324999999999996,66.35444444444444,47.715555555555554,134.20000000000002 +66.40388888888889,48.49722222222222,66.40388888888889,50.3625,66.40388888888889,47.75111111111111,134.3 +66.45333333333333,48.53333333333333,66.45333333333333,50.4,66.45333333333333,47.78666666666667,134.4 +66.50277777777778,48.56944444444444,66.50277777777778,50.4375,66.50277777777778,47.82222222222222,134.5 +66.55222222222223,48.605555555555554,66.55222222222223,50.475,66.55222222222223,47.85777777777778,134.6 +66.60166666666666,48.64166666666666,66.60166666666666,50.512499999999996,66.60166666666666,47.89333333333333,134.70000000000002 +66.6511111111111,48.67777777777777,66.6511111111111,50.55,66.6511111111111,47.92888888888889,134.8 +66.70055555555555,48.71388888888888,66.70055555555555,50.5875,66.70055555555555,47.964444444444446,134.9 +66.75,48.74999999999999,66.75,50.625,66.75,48.0,135.0 +66.79944444444445,48.786111111111104,66.79944444444445,50.6625,66.79944444444445,48.035555555555554,135.1 +66.8488888888889,48.822222222222216,66.8488888888889,50.699999999999996,66.8488888888889,48.07111111111111,135.20000000000002 +66.89833333333333,48.85833333333333,66.89833333333333,50.7375,66.89833333333333,48.10666666666667,135.3 +66.94777777777777,48.89444444444444,66.94777777777777,50.775,66.94777777777777,48.14222222222222,135.4 +66.99722222222222,48.93055555555555,66.99722222222222,50.8125,66.99722222222222,48.17777777777778,135.5 +67.04666666666667,48.96666666666666,67.04666666666667,50.85,67.04666666666667,48.21333333333333,135.6 +67.09611111111111,49.00277777777777,67.09611111111111,50.887499999999996,67.09611111111111,48.24888888888889,135.70000000000002 +67.14555555555556,49.038888888888884,67.14555555555556,50.925,67.14555555555556,48.284444444444446,135.8 +67.195,49.074999999999996,67.195,50.9625,67.195,48.32,135.9 +67.24444444444444,49.11111111111111,67.24444444444444,51.0,67.24444444444444,48.355555555555554,136.0 +67.29388888888889,49.14722222222222,67.29388888888889,51.0375,67.29388888888889,48.39111111111111,136.1 +67.34333333333333,49.18333333333333,67.34333333333333,51.074999999999996,67.34333333333333,48.42666666666667,136.20000000000002 +67.39277777777778,49.21944444444444,67.39277777777778,51.1125,67.39277777777778,48.46222222222222,136.3 +67.44222222222223,49.25555555555555,67.44222222222223,51.15,67.44222222222223,48.49777777777778,136.4 +67.49166666666666,49.291666666666664,67.49166666666666,51.1875,67.49166666666666,48.53333333333333,136.5 +67.5411111111111,49.327777777777776,67.5411111111111,51.225,67.5411111111111,48.568888888888885,136.6 +67.59055555555555,49.36388888888889,67.59055555555555,51.262499999999996,67.59055555555555,48.60444444444445,136.70000000000002 +67.64,49.4,67.64,51.3,67.64,48.64,136.8 +67.68944444444445,49.43611111111111,67.68944444444445,51.3375,67.68944444444445,48.675555555555555,136.9 +67.7388888888889,49.472222222222214,67.7388888888889,51.375,67.7388888888889,48.71111111111111,137.0 +67.78833333333333,49.508333333333326,67.78833333333333,51.4125,67.78833333333333,48.74666666666667,137.1 +67.83777777777777,49.54444444444444,67.83777777777777,51.449999999999996,67.83777777777777,48.782222222222224,137.20000000000002 +67.88722222222222,49.58055555555555,67.88722222222222,51.4875,67.88722222222222,48.81777777777778,137.3 +67.93666666666667,49.61666666666666,67.93666666666667,51.525,67.93666666666667,48.85333333333333,137.4 +67.98611111111111,49.65277777777777,67.98611111111111,51.5625,67.98611111111111,48.888888888888886,137.5 +68.03555555555556,49.68888888888888,68.03555555555556,51.6,68.03555555555556,48.92444444444445,137.6 +68.085,49.724999999999994,68.085,51.637499999999996,68.085,48.96,137.70000000000002 +68.13444444444444,49.761111111111106,68.13444444444444,51.675,68.13444444444444,48.995555555555555,137.8 +68.18388888888889,49.79722222222222,68.18388888888889,51.7125,68.18388888888889,49.03111111111111,137.9 +68.23333333333333,49.83333333333333,68.23333333333333,51.75,68.23333333333333,49.06666666666667,138.0 +68.28277777777778,49.86944444444444,68.28277777777778,51.7875,68.28277777777778,49.102222222222224,138.1 +68.33222222222223,49.90555555555555,68.33222222222223,51.824999999999996,68.33222222222223,49.13777777777778,138.20000000000002 +68.38166666666666,49.94166666666666,68.38166666666666,51.8625,68.38166666666666,49.17333333333333,138.3 +68.43111111111111,49.977777777777774,68.43111111111111,51.9,68.43111111111111,49.208888888888886,138.4 +68.48055555555555,50.013888888888886,68.48055555555555,51.9375,68.48055555555555,49.24444444444445,138.5 +68.53,50.05,68.53,51.975,68.53,49.28,138.6 +68.57944444444445,50.08611111111111,68.57944444444445,52.012499999999996,68.57944444444445,49.315555555555555,138.70000000000002 +68.6288888888889,50.12222222222222,68.6288888888889,52.05,68.6288888888889,49.35111111111111,138.8 +68.67833333333333,50.15833333333333,68.67833333333333,52.0875,68.67833333333333,49.38666666666666,138.9 +68.72777777777777,50.19444444444444,68.72777777777777,52.125,68.72777777777777,49.422222222222224,139.0 +68.77722222222222,50.230555555555554,68.77722222222222,52.1625,68.77722222222222,49.45777777777778,139.1 +68.82666666666667,50.26666666666666,68.82666666666667,52.199999999999996,68.82666666666667,49.49333333333333,139.20000000000002 +68.87611111111111,50.30277777777777,68.87611111111111,52.2375,68.87611111111111,49.528888888888886,139.3 +68.92555555555555,50.33888888888888,68.92555555555555,52.275,68.92555555555555,49.56444444444445,139.4 +68.975,50.37499999999999,68.975,52.3125,68.975,49.6,139.5 +69.02444444444444,50.411111111111104,69.02444444444444,52.35,69.02444444444444,49.635555555555555,139.6 +69.07388888888889,50.447222222222216,69.07388888888889,52.387499999999996,69.07388888888889,49.67111111111111,139.70000000000002 +69.12333333333333,50.48333333333333,69.12333333333333,52.425,69.12333333333333,49.70666666666666,139.8 +69.17277777777778,50.51944444444444,69.17277777777778,52.4625,69.17277777777778,49.742222222222225,139.9 +69.22222222222221,50.55555555555555,69.22222222222221,52.5,69.22222222222221,49.77777777777778,140.0 +69.27166666666666,50.59166666666666,69.27166666666666,52.5375,69.27166666666666,49.81333333333333,140.1 +69.32111111111111,50.62777777777777,69.32111111111111,52.574999999999996,69.32111111111111,49.84888888888889,140.20000000000002 +69.37055555555555,50.663888888888884,69.37055555555555,52.6125,69.37055555555555,49.88444444444445,140.3 +69.42,50.699999999999996,69.42,52.65,69.42,49.92,140.4 +69.46944444444445,50.73611111111111,69.46944444444445,52.6875,69.46944444444445,49.955555555555556,140.5 +69.51888888888888,50.77222222222222,69.51888888888888,52.725,69.51888888888888,49.99111111111111,140.6 +69.56833333333333,50.80833333333333,69.56833333333333,52.762499999999996,69.56833333333333,50.026666666666664,140.70000000000002 +69.61777777777777,50.84444444444444,69.61777777777777,52.8,69.61777777777777,50.062222222222225,140.8 +69.66722222222222,50.88055555555555,69.66722222222222,52.8375,69.66722222222222,50.09777777777778,140.9 +69.71666666666667,50.916666666666664,69.71666666666667,52.875,69.71666666666667,50.13333333333333,141.0 +69.76611111111112,50.952777777777776,69.76611111111112,52.9125,69.76611111111112,50.16888888888889,141.1 +69.81555555555555,50.98888888888889,69.81555555555555,52.949999999999996,69.81555555555555,50.20444444444444,141.20000000000002 +69.865,51.025,69.865,52.9875,69.865,50.24,141.3 +69.91444444444444,51.0611111111111,69.91444444444444,53.025,69.91444444444444,50.275555555555556,141.4 +69.96388888888889,51.097222222222214,69.96388888888889,53.0625,69.96388888888889,50.31111111111111,141.5 +70.01333333333334,51.133333333333326,70.01333333333334,53.1,70.01333333333334,50.346666666666664,141.6 +70.06277777777778,51.16944444444444,70.06277777777778,53.137499999999996,70.06277777777778,50.382222222222225,141.70000000000002 +70.11222222222221,51.20555555555555,70.11222222222221,53.175,70.11222222222221,50.41777777777778,141.8 +70.16166666666666,51.24166666666666,70.16166666666666,53.2125,70.16166666666666,50.45333333333333,141.9 +70.21111111111111,51.27777777777777,70.21111111111111,53.25,70.21111111111111,50.48888888888889,142.0 +70.26055555555556,51.31388888888888,70.26055555555556,53.2875,70.26055555555556,50.52444444444444,142.1 +70.31,51.349999999999994,70.31,53.324999999999996,70.31,50.56,142.20000000000002 +70.35944444444445,51.386111111111106,70.35944444444445,53.3625,70.35944444444445,50.595555555555556,142.3 +70.40888888888888,51.42222222222222,70.40888888888888,53.4,70.40888888888888,50.63111111111111,142.4 +70.45833333333333,51.45833333333333,70.45833333333333,53.4375,70.45833333333333,50.666666666666664,142.5 +70.50777777777778,51.49444444444444,70.50777777777778,53.475,70.50777777777778,50.702222222222225,142.6 +70.55722222222222,51.53055555555555,70.55722222222222,53.512499999999996,70.55722222222222,50.73777777777778,142.70000000000002 +70.60666666666667,51.56666666666666,70.60666666666667,53.55,70.60666666666667,50.77333333333333,142.8 +70.65611111111112,51.602777777777774,70.65611111111112,53.5875,70.65611111111112,50.80888888888889,142.9 +70.70555555555555,51.638888888888886,70.70555555555555,53.625,70.70555555555555,50.84444444444444,143.0 +70.755,51.675,70.755,53.6625,70.755,50.88,143.1 +70.80444444444444,51.71111111111111,70.80444444444444,53.699999999999996,70.80444444444444,50.91555555555556,143.20000000000002 +70.85388888888889,51.74722222222222,70.85388888888889,53.7375,70.85388888888889,50.95111111111111,143.3 +70.90333333333334,51.78333333333333,70.90333333333334,53.775,70.90333333333334,50.986666666666665,143.4 +70.95277777777778,51.81944444444444,70.95277777777778,53.8125,70.95277777777778,51.022222222222226,143.5 +71.00222222222222,51.85555555555555,71.00222222222222,53.85,71.00222222222222,51.05777777777778,143.6 +71.05166666666666,51.89166666666666,71.05166666666666,53.887499999999996,71.05166666666666,51.093333333333334,143.70000000000002 +71.10111111111111,51.92777777777777,71.10111111111111,53.925,71.10111111111111,51.12888888888889,143.8 +71.15055555555556,51.96388888888888,71.15055555555556,53.9625,71.15055555555556,51.16444444444444,143.9 +71.2,51.99999999999999,71.2,54.0,71.2,51.2,144.0 +71.24944444444445,52.036111111111104,71.24944444444445,54.0375,71.24944444444445,51.23555555555556,144.1 +71.29888888888888,52.072222222222216,71.29888888888888,54.074999999999996,71.29888888888888,51.27111111111111,144.20000000000002 +71.34833333333333,52.10833333333333,71.34833333333333,54.1125,71.34833333333333,51.306666666666665,144.3 +71.39777777777778,52.14444444444444,71.39777777777778,54.15,71.39777777777778,51.34222222222222,144.4 +71.44722222222222,52.18055555555555,71.44722222222222,54.1875,71.44722222222222,51.37777777777778,144.5 +71.49666666666667,52.21666666666666,71.49666666666667,54.225,71.49666666666667,51.413333333333334,144.6 +71.54611111111112,52.25277777777777,71.54611111111112,54.262499999999996,71.54611111111112,51.44888888888889,144.70000000000002 +71.59555555555555,52.288888888888884,71.59555555555555,54.3,71.59555555555555,51.48444444444444,144.8 +71.645,52.324999999999996,71.645,54.3375,71.645,51.52,144.9 +71.69444444444444,52.36111111111111,71.69444444444444,54.375,71.69444444444444,51.55555555555556,145.0 +71.74388888888889,52.39722222222222,71.74388888888889,54.4125,71.74388888888889,51.59111111111111,145.1 +71.79333333333334,52.43333333333333,71.79333333333334,54.449999999999996,71.79333333333334,51.626666666666665,145.20000000000002 +71.84277777777778,52.46944444444444,71.84277777777778,54.4875,71.84277777777778,51.66222222222222,145.3 +71.89222222222222,52.50555555555555,71.89222222222222,54.525,71.89222222222222,51.69777777777778,145.4 +71.94166666666666,52.541666666666664,71.94166666666666,54.5625,71.94166666666666,51.733333333333334,145.5 +71.99111111111111,52.577777777777776,71.99111111111111,54.6,71.99111111111111,51.76888888888889,145.6 +72.04055555555556,52.61388888888889,72.04055555555556,54.637499999999996,72.04055555555556,51.80444444444444,145.70000000000002 +72.09,52.65,72.09,54.675,72.09,51.84,145.8 +72.13944444444445,52.6861111111111,72.13944444444445,54.7125,72.13944444444445,51.87555555555556,145.9 +72.18888888888888,52.722222222222214,72.18888888888888,54.75,72.18888888888888,51.91111111111111,146.0 +72.23833333333333,52.758333333333326,72.23833333333333,54.7875,72.23833333333333,51.946666666666665,146.1 +72.28777777777778,52.79444444444444,72.28777777777778,54.824999999999996,72.28777777777778,51.98222222222222,146.20000000000002 +72.33722222222222,52.83055555555555,72.33722222222222,54.8625,72.33722222222222,52.01777777777778,146.3 +72.38666666666667,52.86666666666666,72.38666666666667,54.9,72.38666666666667,52.053333333333335,146.4 +72.4361111111111,52.90277777777777,72.4361111111111,54.9375,72.4361111111111,52.08888888888889,146.5 +72.48555555555555,52.93888888888888,72.48555555555555,54.975,72.48555555555555,52.12444444444444,146.6 +72.535,52.974999999999994,72.535,55.012499999999996,72.535,52.16,146.70000000000002 +72.58444444444444,53.011111111111106,72.58444444444444,55.05,72.58444444444444,52.19555555555556,146.8 +72.63388888888889,53.04722222222222,72.63388888888889,55.0875,72.63388888888889,52.23111111111111,146.9 +72.68333333333334,53.08333333333333,72.68333333333334,55.125,72.68333333333334,52.266666666666666,147.0 +72.73277777777777,53.11944444444444,72.73277777777777,55.1625,72.73277777777777,52.30222222222222,147.1 +72.78222222222222,53.15555555555555,72.78222222222222,55.199999999999996,72.78222222222222,52.33777777777778,147.20000000000002 +72.83166666666666,53.19166666666666,72.83166666666666,55.2375,72.83166666666666,52.373333333333335,147.3 +72.88111111111111,53.227777777777774,72.88111111111111,55.275,72.88111111111111,52.40888888888889,147.4 +72.93055555555556,53.263888888888886,72.93055555555556,55.3125,72.93055555555556,52.44444444444444,147.5 +72.98,53.3,72.98,55.35,72.98,52.48,147.6 +73.02944444444444,53.33611111111111,73.02944444444444,55.387499999999996,73.02944444444444,52.51555555555556,147.70000000000002 +73.07888888888888,53.37222222222222,73.07888888888888,55.425,73.07888888888888,52.55111111111111,147.8 +73.12833333333333,53.40833333333333,73.12833333333333,55.4625,73.12833333333333,52.586666666666666,147.9 +73.17777777777778,53.44444444444444,73.17777777777778,55.5,73.17777777777778,52.62222222222222,148.0 +73.22722222222222,53.48055555555555,73.22722222222222,55.5375,73.22722222222222,52.65777777777778,148.1 +73.27666666666667,53.51666666666666,73.27666666666667,55.574999999999996,73.27666666666667,52.693333333333335,148.20000000000002 +73.3261111111111,53.55277777777777,73.3261111111111,55.6125,73.3261111111111,52.72888888888889,148.3 +73.37555555555555,53.58888888888888,73.37555555555555,55.65,73.37555555555555,52.76444444444444,148.4 +73.425,53.62499999999999,73.425,55.6875,73.425,52.8,148.5 +73.47444444444444,53.661111111111104,73.47444444444444,55.725,73.47444444444444,52.83555555555556,148.6 +73.52388888888889,53.697222222222216,73.52388888888889,55.762499999999996,73.52388888888889,52.87111111111111,148.70000000000002 +73.57333333333334,53.73333333333333,73.57333333333334,55.8,73.57333333333334,52.906666666666666,148.8 +73.62277777777777,53.76944444444444,73.62277777777777,55.8375,73.62277777777777,52.94222222222222,148.9 +73.67222222222222,53.80555555555555,73.67222222222222,55.875,73.67222222222222,52.977777777777774,149.0 +73.72166666666666,53.84166666666666,73.72166666666666,55.9125,73.72166666666666,53.013333333333335,149.1 +73.77111111111111,53.87777777777777,73.77111111111111,55.949999999999996,73.77111111111111,53.04888888888889,149.20000000000002 +73.82055555555556,53.913888888888884,73.82055555555556,55.9875,73.82055555555556,53.08444444444444,149.3 +73.87,53.949999999999996,73.87,56.025,73.87,53.12,149.4 +73.91944444444444,53.98611111111111,73.91944444444444,56.0625,73.91944444444444,53.15555555555556,149.5 +73.96888888888888,54.02222222222222,73.96888888888888,56.1,73.96888888888888,53.19111111111111,149.6 +74.01833333333333,54.05833333333333,74.01833333333333,56.137499999999996,74.01833333333333,53.22666666666667,149.70000000000002 +74.06777777777778,54.09444444444444,74.06777777777778,56.175,74.06777777777778,53.26222222222222,149.8 +74.11722222222222,54.13055555555555,74.11722222222222,56.2125,74.11722222222222,53.297777777777775,149.9 +74.16666666666667,54.166666666666664,74.16666666666667,56.25,74.16666666666667,53.333333333333336,150.0 +74.2161111111111,54.202777777777776,74.2161111111111,56.2875,74.2161111111111,53.36888888888889,150.1 +74.26555555555555,54.23888888888889,74.26555555555555,56.324999999999996,74.26555555555555,53.404444444444444,150.20000000000002 +74.315,54.27499999999999,74.315,56.3625,74.315,53.44,150.3 +74.36444444444444,54.3111111111111,74.36444444444444,56.4,74.36444444444444,53.47555555555556,150.4 +74.41388888888889,54.347222222222214,74.41388888888889,56.4375,74.41388888888889,53.51111111111111,150.5 +74.46333333333334,54.383333333333326,74.46333333333334,56.475,74.46333333333334,53.54666666666667,150.6 +74.51277777777777,54.41944444444444,74.51277777777777,56.512499999999996,74.51277777777777,53.58222222222222,150.70000000000002 +74.56222222222222,54.45555555555555,74.56222222222222,56.55,74.56222222222222,53.617777777777775,150.8 +74.61166666666666,54.49166666666666,74.61166666666666,56.5875,74.61166666666666,53.653333333333336,150.9 +74.66111111111111,54.52777777777777,74.66111111111111,56.625,74.66111111111111,53.68888888888889,151.0 +74.71055555555556,54.56388888888888,74.71055555555556,56.6625,74.71055555555556,53.724444444444444,151.1 +74.76,54.599999999999994,74.76,56.699999999999996,74.76,53.76,151.20000000000002 +74.80944444444444,54.636111111111106,74.80944444444444,56.7375,74.80944444444444,53.79555555555555,151.3 +74.85888888888888,54.67222222222222,74.85888888888888,56.775,74.85888888888888,53.83111111111111,151.4 +74.90833333333333,54.70833333333333,74.90833333333333,56.8125,74.90833333333333,53.86666666666667,151.5 +74.95777777777778,54.74444444444444,74.95777777777778,56.85,74.95777777777778,53.90222222222222,151.6 +75.00722222222223,54.78055555555555,75.00722222222223,56.887499999999996,75.00722222222223,53.937777777777775,151.70000000000002 +75.05666666666667,54.81666666666666,75.05666666666667,56.925,75.05666666666667,53.973333333333336,151.8 +75.1061111111111,54.852777777777774,75.1061111111111,56.9625,75.1061111111111,54.00888888888889,151.9 +75.15555555555555,54.888888888888886,75.15555555555555,57.0,75.15555555555555,54.044444444444444,152.0 +75.205,54.925,75.205,57.0375,75.205,54.08,152.1 +75.25444444444445,54.96111111111111,75.25444444444445,57.074999999999996,75.25444444444445,54.11555555555555,152.20000000000002 +75.30388888888889,54.99722222222222,75.30388888888889,57.1125,75.30388888888889,54.15111111111111,152.3 +75.35333333333334,55.03333333333333,75.35333333333334,57.15,75.35333333333334,54.18666666666667,152.4 +75.40277777777777,55.069444444444436,75.40277777777777,57.1875,75.40277777777777,54.22222222222222,152.5 +75.45222222222222,55.10555555555555,75.45222222222222,57.225,75.45222222222222,54.257777777777775,152.6 +75.50166666666667,55.14166666666666,75.50166666666667,57.262499999999996,75.50166666666667,54.29333333333334,152.70000000000002 +75.55111111111111,55.17777777777777,75.55111111111111,57.3,75.55111111111111,54.32888888888889,152.8 +75.60055555555556,55.21388888888888,75.60055555555556,57.3375,75.60055555555556,54.364444444444445,152.9 +75.65,55.24999999999999,75.65,57.375,75.65,54.4,153.0 +75.69944444444444,55.286111111111104,75.69944444444444,57.4125,75.69944444444444,54.43555555555555,153.1 +75.74888888888889,55.322222222222216,75.74888888888889,57.449999999999996,75.74888888888889,54.471111111111114,153.20000000000002 +75.79833333333333,55.35833333333333,75.79833333333333,57.4875,75.79833333333333,54.50666666666667,153.3 +75.84777777777778,55.39444444444444,75.84777777777778,57.525,75.84777777777778,54.54222222222222,153.4 +75.89722222222223,55.43055555555555,75.89722222222223,57.5625,75.89722222222223,54.577777777777776,153.5 +75.94666666666666,55.46666666666666,75.94666666666666,57.599999999999994,75.94666666666666,54.61333333333333,153.60000000000002 +75.9961111111111,55.50277777777777,75.9961111111111,57.637499999999996,75.9961111111111,54.64888888888889,153.70000000000002 +76.04555555555555,55.538888888888884,76.04555555555555,57.675,76.04555555555555,54.684444444444445,153.8 +76.095,55.574999999999996,76.095,57.7125,76.095,54.72,153.9 +76.14444444444445,55.61111111111111,76.14444444444445,57.75,76.14444444444445,54.75555555555555,154.0 +76.19388888888889,55.64722222222222,76.19388888888889,57.787499999999994,76.19388888888889,54.791111111111114,154.10000000000002 +76.24333333333333,55.68333333333333,76.24333333333333,57.824999999999996,76.24333333333333,54.82666666666667,154.20000000000002 +76.29277777777777,55.71944444444444,76.29277777777777,57.8625,76.29277777777777,54.86222222222222,154.3 +76.34222222222222,55.75555555555555,76.34222222222222,57.9,76.34222222222222,54.897777777777776,154.4 +76.39166666666667,55.791666666666664,76.39166666666667,57.9375,76.39166666666667,54.93333333333333,154.5 +76.44111111111111,55.827777777777776,76.44111111111111,57.974999999999994,76.44111111111111,54.96888888888889,154.60000000000002 +76.49055555555556,55.86388888888889,76.49055555555556,58.012499999999996,76.49055555555556,55.004444444444445,154.70000000000002 +76.53999999999999,55.89999999999999,76.53999999999999,58.05,76.53999999999999,55.04,154.8 +76.58944444444444,55.9361111111111,76.58944444444444,58.0875,76.58944444444444,55.07555555555555,154.9 +76.63888888888889,55.972222222222214,76.63888888888889,58.125,76.63888888888889,55.111111111111114,155.0 +76.68833333333333,56.008333333333326,76.68833333333333,58.162499999999994,76.68833333333333,55.14666666666667,155.10000000000002 +76.73777777777778,56.04444444444444,76.73777777777778,58.199999999999996,76.73777777777778,55.18222222222222,155.20000000000002 +76.78722222222223,56.08055555555555,76.78722222222223,58.2375,76.78722222222223,55.217777777777776,155.3 +76.83666666666666,56.11666666666666,76.83666666666666,58.275,76.83666666666666,55.25333333333333,155.4 +76.8861111111111,56.15277777777777,76.8861111111111,58.3125,76.8861111111111,55.28888888888889,155.5 +76.93555555555555,56.18888888888888,76.93555555555555,58.349999999999994,76.93555555555555,55.324444444444445,155.60000000000002 +76.985,56.224999999999994,76.985,58.387499999999996,76.985,55.36,155.70000000000002 +77.03444444444445,56.261111111111106,77.03444444444445,58.425,77.03444444444445,55.39555555555555,155.8 +77.0838888888889,56.29722222222222,77.0838888888889,58.4625,77.0838888888889,55.431111111111115,155.9 +77.13333333333333,56.33333333333333,77.13333333333333,58.5,77.13333333333333,55.46666666666667,156.0 +77.18277777777777,56.36944444444444,77.18277777777777,58.537499999999994,77.18277777777777,55.50222222222222,156.10000000000002 +77.23222222222222,56.40555555555555,77.23222222222222,58.574999999999996,77.23222222222222,55.53777777777778,156.20000000000002 +77.28166666666667,56.44166666666666,77.28166666666667,58.6125,77.28166666666667,55.57333333333333,156.3 +77.33111111111111,56.477777777777774,77.33111111111111,58.65,77.33111111111111,55.60888888888889,156.4 +77.38055555555556,56.513888888888886,77.38055555555556,58.6875,77.38055555555556,55.644444444444446,156.5 +77.42999999999999,56.55,77.42999999999999,58.724999999999994,77.42999999999999,55.68,156.60000000000002 +77.47944444444444,56.58611111111111,77.47944444444444,58.762499999999996,77.47944444444444,55.715555555555554,156.70000000000002 +77.52888888888889,56.62222222222222,77.52888888888889,58.8,77.52888888888889,55.75111111111111,156.8 +77.57833333333333,56.65833333333333,77.57833333333333,58.8375,77.57833333333333,55.78666666666667,156.9 +77.62777777777778,56.694444444444436,77.62777777777778,58.875,77.62777777777778,55.82222222222222,157.0 +77.67722222222223,56.73055555555555,77.67722222222223,58.912499999999994,77.67722222222223,55.85777777777778,157.10000000000002 +77.72666666666666,56.76666666666666,77.72666666666666,58.949999999999996,77.72666666666666,55.89333333333333,157.20000000000002 +77.7761111111111,56.80277777777777,77.7761111111111,58.9875,77.7761111111111,55.92888888888889,157.3 +77.82555555555555,56.83888888888888,77.82555555555555,59.025,77.82555555555555,55.964444444444446,157.4 +77.875,56.87499999999999,77.875,59.0625,77.875,56.0,157.5 +77.92444444444445,56.911111111111104,77.92444444444445,59.099999999999994,77.92444444444445,56.035555555555554,157.60000000000002 +77.9738888888889,56.947222222222216,77.9738888888889,59.137499999999996,77.9738888888889,56.07111111111111,157.70000000000002 +78.02333333333333,56.98333333333333,78.02333333333333,59.175,78.02333333333333,56.10666666666667,157.8 +78.07277777777777,57.01944444444444,78.07277777777777,59.2125,78.07277777777777,56.14222222222222,157.9 +78.12222222222222,57.05555555555555,78.12222222222222,59.25,78.12222222222222,56.17777777777778,158.0 +78.17166666666667,57.09166666666666,78.17166666666667,59.287499999999994,78.17166666666667,56.21333333333333,158.10000000000002 +78.22111111111111,57.12777777777777,78.22111111111111,59.324999999999996,78.22111111111111,56.24888888888889,158.20000000000002 +78.27055555555556,57.163888888888884,78.27055555555556,59.3625,78.27055555555556,56.284444444444446,158.3 +78.32,57.199999999999996,78.32,59.4,78.32,56.32,158.4 +78.36944444444444,57.23611111111111,78.36944444444444,59.4375,78.36944444444444,56.355555555555554,158.5 +78.41888888888889,57.27222222222222,78.41888888888889,59.474999999999994,78.41888888888889,56.39111111111111,158.60000000000002 +78.46833333333333,57.30833333333333,78.46833333333333,59.512499999999996,78.46833333333333,56.42666666666667,158.70000000000002 +78.51777777777778,57.34444444444444,78.51777777777778,59.55,78.51777777777778,56.46222222222222,158.8 +78.56722222222223,57.38055555555555,78.56722222222223,59.5875,78.56722222222223,56.49777777777778,158.9 +78.61666666666666,57.416666666666664,78.61666666666666,59.625,78.61666666666666,56.53333333333333,159.0 +78.6661111111111,57.452777777777776,78.6661111111111,59.662499999999994,78.6661111111111,56.568888888888885,159.10000000000002 +78.71555555555555,57.48888888888888,78.71555555555555,59.699999999999996,78.71555555555555,56.60444444444445,159.20000000000002 +78.765,57.52499999999999,78.765,59.7375,78.765,56.64,159.3 +78.81444444444445,57.5611111111111,78.81444444444445,59.775,78.81444444444445,56.675555555555555,159.4 +78.8638888888889,57.597222222222214,78.8638888888889,59.8125,78.8638888888889,56.71111111111111,159.5 +78.91333333333333,57.633333333333326,78.91333333333333,59.849999999999994,78.91333333333333,56.74666666666667,159.60000000000002 +78.96277777777777,57.66944444444444,78.96277777777777,59.887499999999996,78.96277777777777,56.782222222222224,159.70000000000002 +79.01222222222222,57.70555555555555,79.01222222222222,59.925,79.01222222222222,56.81777777777778,159.8 +79.06166666666667,57.74166666666666,79.06166666666667,59.9625,79.06166666666667,56.85333333333333,159.9 +79.11111111111111,57.77777777777777,79.11111111111111,60.0,79.11111111111111,56.888888888888886,160.0 +79.16055555555556,57.81388888888888,79.16055555555556,60.037499999999994,79.16055555555556,56.92444444444445,160.10000000000002 +79.21,57.849999999999994,79.21,60.074999999999996,79.21,56.96,160.20000000000002 +79.25944444444444,57.886111111111106,79.25944444444444,60.1125,79.25944444444444,56.995555555555555,160.3 +79.30888888888889,57.92222222222222,79.30888888888889,60.15,79.30888888888889,57.03111111111111,160.4 +79.35833333333333,57.95833333333333,79.35833333333333,60.1875,79.35833333333333,57.06666666666667,160.5 +79.40777777777778,57.99444444444444,79.40777777777778,60.224999999999994,79.40777777777778,57.102222222222224,160.60000000000002 +79.45722222222223,58.03055555555555,79.45722222222223,60.262499999999996,79.45722222222223,57.13777777777778,160.70000000000002 +79.50666666666666,58.06666666666666,79.50666666666666,60.3,79.50666666666666,57.17333333333333,160.8 +79.55611111111111,58.102777777777774,79.55611111111111,60.3375,79.55611111111111,57.208888888888886,160.9 +79.60555555555555,58.138888888888886,79.60555555555555,60.375,79.60555555555555,57.24444444444445,161.0 +79.655,58.175,79.655,60.412499999999994,79.655,57.28,161.10000000000002 +79.70444444444445,58.21111111111111,79.70444444444445,60.449999999999996,79.70444444444445,57.315555555555555,161.20000000000002 +79.75388888888888,58.24722222222222,79.75388888888888,60.4875,79.75388888888888,57.35111111111111,161.3 +79.80333333333333,58.283333333333324,79.80333333333333,60.525,79.80333333333333,57.38666666666666,161.4 +79.85277777777777,58.319444444444436,79.85277777777777,60.5625,79.85277777777777,57.422222222222224,161.5 +79.90222222222222,58.35555555555555,79.90222222222222,60.599999999999994,79.90222222222222,57.45777777777778,161.60000000000002 +79.95166666666667,58.39166666666666,79.95166666666667,60.637499999999996,79.95166666666667,57.49333333333333,161.70000000000002 +80.00111111111111,58.42777777777777,80.00111111111111,60.675,80.00111111111111,57.528888888888886,161.8 +80.05055555555555,58.46388888888888,80.05055555555555,60.7125,80.05055555555555,57.56444444444445,161.9 +80.1,58.49999999999999,80.1,60.75,80.1,57.6,162.0 +80.14944444444444,58.536111111111104,80.14944444444444,60.787499999999994,80.14944444444444,57.635555555555555,162.10000000000002 +80.19888888888889,58.572222222222216,80.19888888888889,60.824999999999996,80.19888888888889,57.67111111111111,162.20000000000002 +80.24833333333333,58.60833333333333,80.24833333333333,60.8625,80.24833333333333,57.70666666666666,162.3 +80.29777777777778,58.64444444444444,80.29777777777778,60.9,80.29777777777778,57.742222222222225,162.4 +80.34722222222221,58.68055555555555,80.34722222222221,60.9375,80.34722222222221,57.77777777777778,162.5 +80.39666666666666,58.71666666666666,80.39666666666666,60.974999999999994,80.39666666666666,57.81333333333333,162.60000000000002 +80.44611111111111,58.75277777777777,80.44611111111111,61.012499999999996,80.44611111111111,57.84888888888889,162.70000000000002 +80.49555555555555,58.788888888888884,80.49555555555555,61.05,80.49555555555555,57.88444444444445,162.8 +80.545,58.824999999999996,80.545,61.0875,80.545,57.92,162.9 +80.59444444444445,58.86111111111111,80.59444444444445,61.125,80.59444444444445,57.955555555555556,163.0 +80.64388888888888,58.89722222222222,80.64388888888888,61.162499999999994,80.64388888888888,57.99111111111111,163.10000000000002 +80.69333333333333,58.93333333333333,80.69333333333333,61.199999999999996,80.69333333333333,58.026666666666664,163.20000000000002 +80.74277777777777,58.96944444444444,80.74277777777777,61.2375,80.74277777777777,58.062222222222225,163.3 +80.79222222222222,59.00555555555555,80.79222222222222,61.275,80.79222222222222,58.09777777777778,163.4 +80.84166666666667,59.041666666666664,80.84166666666667,61.3125,80.84166666666667,58.13333333333333,163.5 +80.89111111111112,59.077777777777776,80.89111111111112,61.349999999999994,80.89111111111112,58.16888888888889,163.60000000000002 +80.94055555555555,59.11388888888888,80.94055555555555,61.387499999999996,80.94055555555555,58.20444444444444,163.70000000000002 +80.99,59.14999999999999,80.99,61.425,80.99,58.24,163.8 +81.03944444444444,59.1861111111111,81.03944444444444,61.4625,81.03944444444444,58.275555555555556,163.9 +81.08888888888889,59.222222222222214,81.08888888888889,61.5,81.08888888888889,58.31111111111111,164.0 +81.13833333333334,59.258333333333326,81.13833333333334,61.537499999999994,81.13833333333334,58.346666666666664,164.10000000000002 +81.18777777777778,59.29444444444444,81.18777777777778,61.574999999999996,81.18777777777778,58.382222222222225,164.20000000000002 +81.23722222222221,59.33055555555555,81.23722222222221,61.6125,81.23722222222221,58.41777777777778,164.3 +81.28666666666666,59.36666666666666,81.28666666666666,61.65,81.28666666666666,58.45333333333333,164.4 +81.33611111111111,59.40277777777777,81.33611111111111,61.6875,81.33611111111111,58.48888888888889,164.5 +81.38555555555556,59.43888888888888,81.38555555555556,61.724999999999994,81.38555555555556,58.52444444444444,164.60000000000002 +81.435,59.474999999999994,81.435,61.762499999999996,81.435,58.56,164.70000000000002 +81.48444444444445,59.511111111111106,81.48444444444445,61.8,81.48444444444445,58.595555555555556,164.8 +81.53388888888888,59.54722222222222,81.53388888888888,61.8375,81.53388888888888,58.63111111111111,164.9 +81.58333333333333,59.58333333333333,81.58333333333333,61.875,81.58333333333333,58.666666666666664,165.0 +81.63277777777778,59.61944444444444,81.63277777777778,61.912499999999994,81.63277777777778,58.702222222222225,165.10000000000002 +81.68222222222222,59.65555555555555,81.68222222222222,61.949999999999996,81.68222222222222,58.73777777777778,165.20000000000002 +81.73166666666667,59.69166666666666,81.73166666666667,61.9875,81.73166666666667,58.77333333333333,165.3 +81.78111111111112,59.727777777777774,81.78111111111112,62.025,81.78111111111112,58.80888888888889,165.4 +81.83055555555555,59.763888888888886,81.83055555555555,62.0625,81.83055555555555,58.84444444444444,165.5 +81.88,59.8,81.88,62.099999999999994,81.88,58.88,165.60000000000002 +81.92944444444444,59.83611111111111,81.92944444444444,62.137499999999996,81.92944444444444,58.91555555555556,165.70000000000002 +81.97888888888889,59.87222222222222,81.97888888888889,62.175,81.97888888888889,58.95111111111111,165.8 +82.02833333333334,59.908333333333324,82.02833333333334,62.2125,82.02833333333334,58.986666666666665,165.9 +82.07777777777778,59.944444444444436,82.07777777777778,62.25,82.07777777777778,59.022222222222226,166.0 +82.12722222222222,59.98055555555555,82.12722222222222,62.287499999999994,82.12722222222222,59.05777777777778,166.10000000000002 +82.17666666666666,60.01666666666666,82.17666666666666,62.324999999999996,82.17666666666666,59.093333333333334,166.20000000000002 +82.22611111111111,60.05277777777777,82.22611111111111,62.3625,82.22611111111111,59.12888888888889,166.3 +82.27555555555556,60.08888888888888,82.27555555555556,62.4,82.27555555555556,59.16444444444444,166.4 +82.325,60.12499999999999,82.325,62.4375,82.325,59.2,166.5 +82.37444444444445,60.161111111111104,82.37444444444445,62.474999999999994,82.37444444444445,59.23555555555556,166.60000000000002 +82.42388888888888,60.197222222222216,82.42388888888888,62.512499999999996,82.42388888888888,59.27111111111111,166.70000000000002 +82.47333333333333,60.23333333333333,82.47333333333333,62.55,82.47333333333333,59.306666666666665,166.8 +82.52277777777778,60.26944444444444,82.52277777777778,62.5875,82.52277777777778,59.34222222222222,166.9 +82.57222222222222,60.30555555555555,82.57222222222222,62.625,82.57222222222222,59.37777777777778,167.0 +82.62166666666667,60.34166666666666,82.62166666666667,62.662499999999994,82.62166666666667,59.413333333333334,167.10000000000002 +82.67111111111112,60.37777777777777,82.67111111111112,62.699999999999996,82.67111111111112,59.44888888888889,167.20000000000002 +82.72055555555555,60.413888888888884,82.72055555555555,62.7375,82.72055555555555,59.48444444444444,167.3 +82.77,60.449999999999996,82.77,62.775,82.77,59.52,167.4 +82.81944444444444,60.48611111111111,82.81944444444444,62.8125,82.81944444444444,59.55555555555556,167.5 +82.86888888888889,60.52222222222222,82.86888888888889,62.849999999999994,82.86888888888889,59.59111111111111,167.60000000000002 +82.91833333333334,60.55833333333333,82.91833333333334,62.887499999999996,82.91833333333334,59.626666666666665,167.70000000000002 +82.96777777777778,60.59444444444444,82.96777777777778,62.925,82.96777777777778,59.66222222222222,167.8 +83.01722222222222,60.63055555555555,83.01722222222222,62.9625,83.01722222222222,59.69777777777778,167.9 +83.06666666666666,60.666666666666664,83.06666666666666,63.0,83.06666666666666,59.733333333333334,168.0 +83.11611111111111,60.70277777777777,83.11611111111111,63.037499999999994,83.11611111111111,59.76888888888889,168.10000000000002 +83.16555555555556,60.73888888888888,83.16555555555556,63.074999999999996,83.16555555555556,59.80444444444444,168.20000000000002 +83.215,60.77499999999999,83.215,63.1125,83.215,59.84,168.3 +83.26444444444444,60.8111111111111,83.26444444444444,63.15,83.26444444444444,59.87555555555556,168.4 +83.31388888888888,60.847222222222214,83.31388888888888,63.1875,83.31388888888888,59.91111111111111,168.5 +83.36333333333333,60.883333333333326,83.36333333333333,63.224999999999994,83.36333333333333,59.946666666666665,168.60000000000002 +83.41277777777778,60.91944444444444,83.41277777777778,63.262499999999996,83.41277777777778,59.98222222222222,168.70000000000002 +83.46222222222222,60.95555555555555,83.46222222222222,63.3,83.46222222222222,60.01777777777778,168.8 +83.51166666666667,60.99166666666666,83.51166666666667,63.3375,83.51166666666667,60.053333333333335,168.9 +83.5611111111111,61.02777777777777,83.5611111111111,63.375,83.5611111111111,60.08888888888889,169.0 +83.61055555555555,61.06388888888888,83.61055555555555,63.412499999999994,83.61055555555555,60.12444444444444,169.10000000000002 +83.66,61.099999999999994,83.66,63.449999999999996,83.66,60.16,169.20000000000002 +83.70944444444444,61.136111111111106,83.70944444444444,63.4875,83.70944444444444,60.19555555555556,169.3 +83.75888888888889,61.17222222222222,83.75888888888889,63.525,83.75888888888889,60.23111111111111,169.4 +83.80833333333334,61.20833333333333,83.80833333333334,63.5625,83.80833333333334,60.266666666666666,169.5 +83.85777777777777,61.24444444444444,83.85777777777777,63.599999999999994,83.85777777777777,60.30222222222222,169.60000000000002 +83.90722222222222,61.28055555555555,83.90722222222222,63.637499999999996,83.90722222222222,60.33777777777778,169.70000000000002 +83.95666666666666,61.31666666666666,83.95666666666666,63.675,83.95666666666666,60.373333333333335,169.8 +84.00611111111111,61.352777777777774,84.00611111111111,63.7125,84.00611111111111,60.40888888888889,169.9 +84.05555555555556,61.388888888888886,84.05555555555556,63.75,84.05555555555556,60.44444444444444,170.0 +84.105,61.425,84.105,63.787499999999994,84.105,60.48,170.10000000000002 +84.15444444444444,61.46111111111111,84.15444444444444,63.824999999999996,84.15444444444444,60.51555555555556,170.20000000000002 +84.20388888888888,61.49722222222221,84.20388888888888,63.8625,84.20388888888888,60.55111111111111,170.3 +84.25333333333333,61.533333333333324,84.25333333333333,63.9,84.25333333333333,60.586666666666666,170.4 +84.30277777777778,61.569444444444436,84.30277777777778,63.9375,84.30277777777778,60.62222222222222,170.5 +84.35222222222222,61.60555555555555,84.35222222222222,63.974999999999994,84.35222222222222,60.65777777777778,170.60000000000002 +84.40166666666667,61.64166666666666,84.40166666666667,64.0125,84.40166666666667,60.693333333333335,170.70000000000002 +84.4511111111111,61.67777777777777,84.4511111111111,64.05,84.4511111111111,60.72888888888889,170.8 +84.50055555555555,61.71388888888888,84.50055555555555,64.08749999999999,84.50055555555555,60.76444444444444,170.9 +84.55,61.74999999999999,84.55,64.125,84.55,60.8,171.0 +84.59944444444444,61.786111111111104,84.59944444444444,64.1625,84.59944444444444,60.83555555555556,171.10000000000002 +84.64888888888889,61.822222222222216,84.64888888888889,64.2,84.64888888888889,60.87111111111111,171.20000000000002 +84.69833333333334,61.85833333333333,84.69833333333334,64.2375,84.69833333333334,60.906666666666666,171.3 +84.74777777777777,61.89444444444444,84.74777777777777,64.27499999999999,84.74777777777777,60.94222222222222,171.4 +84.79722222222222,61.93055555555555,84.79722222222222,64.3125,84.79722222222222,60.977777777777774,171.5 +84.84666666666666,61.96666666666666,84.84666666666666,64.35,84.84666666666666,61.013333333333335,171.60000000000002 +84.89611111111111,62.00277777777777,84.89611111111111,64.3875,84.89611111111111,61.04888888888889,171.70000000000002 +84.94555555555556,62.038888888888884,84.94555555555556,64.425,84.94555555555556,61.08444444444444,171.8 +84.995,62.074999999999996,84.995,64.46249999999999,84.995,61.12,171.9 +85.04444444444444,62.11111111111111,85.04444444444444,64.5,85.04444444444444,61.15555555555556,172.0 +85.09388888888888,62.14722222222222,85.09388888888888,64.5375,85.09388888888888,61.19111111111111,172.10000000000002 +85.14333333333333,62.18333333333333,85.14333333333333,64.575,85.14333333333333,61.22666666666667,172.20000000000002 +85.19277777777778,62.21944444444444,85.19277777777778,64.6125,85.19277777777778,61.26222222222222,172.3 +85.24222222222222,62.25555555555555,85.24222222222222,64.64999999999999,85.24222222222222,61.297777777777775,172.4 +85.29166666666667,62.291666666666664,85.29166666666667,64.6875,85.29166666666667,61.333333333333336,172.5 +85.3411111111111,62.32777777777777,85.3411111111111,64.725,85.3411111111111,61.36888888888889,172.60000000000002 +85.39055555555555,62.36388888888888,85.39055555555555,64.7625,85.39055555555555,61.404444444444444,172.70000000000002 +85.44,62.39999999999999,85.44,64.8,85.44,61.44,172.8 +85.48944444444444,62.4361111111111,85.48944444444444,64.83749999999999,85.48944444444444,61.47555555555556,172.9 +85.53888888888889,62.472222222222214,85.53888888888889,64.875,85.53888888888889,61.51111111111111,173.0 +85.58833333333334,62.508333333333326,85.58833333333334,64.9125,85.58833333333334,61.54666666666667,173.10000000000002 +85.63777777777777,62.54444444444444,85.63777777777777,64.95,85.63777777777777,61.58222222222222,173.20000000000002 +85.68722222222222,62.58055555555555,85.68722222222222,64.9875,85.68722222222222,61.617777777777775,173.3 +85.73666666666666,62.61666666666666,85.73666666666666,65.02499999999999,85.73666666666666,61.653333333333336,173.4 +85.78611111111111,62.65277777777777,85.78611111111111,65.0625,85.78611111111111,61.68888888888889,173.5 +85.83555555555556,62.68888888888888,85.83555555555556,65.1,85.83555555555556,61.724444444444444,173.60000000000002 +85.885,62.724999999999994,85.885,65.1375,85.885,61.76,173.70000000000002 +85.93444444444444,62.761111111111106,85.93444444444444,65.175,85.93444444444444,61.79555555555555,173.8 +85.98388888888888,62.79722222222222,85.98388888888888,65.21249999999999,85.98388888888888,61.83111111111111,173.9 +86.03333333333333,62.83333333333333,86.03333333333333,65.25,86.03333333333333,61.86666666666667,174.0 +86.08277777777778,62.86944444444444,86.08277777777778,65.2875,86.08277777777778,61.90222222222222,174.10000000000002 +86.13222222222223,62.90555555555555,86.13222222222223,65.325,86.13222222222223,61.937777777777775,174.20000000000002 +86.18166666666667,62.94166666666666,86.18166666666667,65.3625,86.18166666666667,61.973333333333336,174.3 +86.2311111111111,62.977777777777774,86.2311111111111,65.39999999999999,86.2311111111111,62.00888888888889,174.4 +86.28055555555555,63.013888888888886,86.28055555555555,65.4375,86.28055555555555,62.044444444444444,174.5 +86.33,63.05,86.33,65.475,86.33,62.08,174.60000000000002 +86.37944444444445,63.08611111111111,86.37944444444445,65.5125,86.37944444444445,62.11555555555555,174.70000000000002 +86.42888888888889,63.12222222222221,86.42888888888889,65.55,86.42888888888889,62.15111111111111,174.8 +86.47833333333334,63.158333333333324,86.47833333333334,65.58749999999999,86.47833333333334,62.18666666666667,174.9 +86.52777777777777,63.194444444444436,86.52777777777777,65.625,86.52777777777777,62.22222222222222,175.0 +86.57722222222222,63.23055555555555,86.57722222222222,65.6625,86.57722222222222,62.257777777777775,175.10000000000002 +86.62666666666667,63.26666666666666,86.62666666666667,65.7,86.62666666666667,62.29333333333334,175.20000000000002 +86.67611111111111,63.30277777777777,86.67611111111111,65.7375,86.67611111111111,62.32888888888889,175.3 +86.72555555555556,63.33888888888888,86.72555555555556,65.77499999999999,86.72555555555556,62.364444444444445,175.4 +86.775,63.37499999999999,86.775,65.8125,86.775,62.4,175.5 +86.82444444444444,63.411111111111104,86.82444444444444,65.85,86.82444444444444,62.43555555555555,175.60000000000002 +86.87388888888889,63.447222222222216,86.87388888888889,65.8875,86.87388888888889,62.471111111111114,175.70000000000002 +86.92333333333333,63.48333333333333,86.92333333333333,65.925,86.92333333333333,62.50666666666667,175.8 +86.97277777777778,63.51944444444444,86.97277777777778,65.96249999999999,86.97277777777778,62.54222222222222,175.9 +87.02222222222223,63.55555555555555,87.02222222222223,66.0,87.02222222222223,62.577777777777776,176.0 +87.07166666666666,63.59166666666666,87.07166666666666,66.0375,87.07166666666666,62.61333333333333,176.10000000000002 +87.1211111111111,63.62777777777777,87.1211111111111,66.075,87.1211111111111,62.64888888888889,176.20000000000002 +87.17055555555555,63.663888888888884,87.17055555555555,66.1125,87.17055555555555,62.684444444444445,176.3 +87.22,63.699999999999996,87.22,66.14999999999999,87.22,62.72,176.4 +87.26944444444445,63.73611111111111,87.26944444444445,66.1875,87.26944444444445,62.75555555555555,176.5 +87.31888888888889,63.77222222222222,87.31888888888889,66.225,87.31888888888889,62.791111111111114,176.60000000000002 +87.36833333333333,63.80833333333333,87.36833333333333,66.2625,87.36833333333333,62.82666666666667,176.70000000000002 +87.41777777777777,63.84444444444444,87.41777777777777,66.3,87.41777777777777,62.86222222222222,176.8 +87.46722222222222,63.88055555555555,87.46722222222222,66.33749999999999,87.46722222222222,62.897777777777776,176.9 +87.51666666666667,63.91666666666666,87.51666666666667,66.375,87.51666666666667,62.93333333333333,177.0 +87.56611111111111,63.95277777777777,87.56611111111111,66.4125,87.56611111111111,62.96888888888889,177.10000000000002 +87.61555555555556,63.98888888888888,87.61555555555556,66.45,87.61555555555556,63.004444444444445,177.20000000000002 +87.66499999999999,64.02499999999999,87.66499999999999,66.4875,87.66499999999999,63.04,177.3 +87.71444444444444,64.0611111111111,87.71444444444444,66.52499999999999,87.71444444444444,63.07555555555555,177.4 +87.76388888888889,64.09722222222221,87.76388888888889,66.5625,87.76388888888889,63.111111111111114,177.5 +87.81333333333333,64.13333333333333,87.81333333333333,66.6,87.81333333333333,63.14666666666667,177.60000000000002 +87.86277777777778,64.16944444444444,87.86277777777778,66.6375,87.86277777777778,63.18222222222222,177.70000000000002 +87.91222222222223,64.20555555555555,87.91222222222223,66.675,87.91222222222223,63.217777777777776,177.8 +87.96166666666666,64.24166666666666,87.96166666666666,66.71249999999999,87.96166666666666,63.25333333333333,177.9 +88.0111111111111,64.27777777777777,88.0111111111111,66.75,88.0111111111111,63.28888888888889,178.0 +88.06055555555555,64.31388888888888,88.06055555555555,66.7875,88.06055555555555,63.324444444444445,178.10000000000002 +88.11,64.35,88.11,66.825,88.11,63.36,178.20000000000002 +88.15944444444445,64.3861111111111,88.15944444444445,66.8625,88.15944444444445,63.39555555555555,178.3 +88.2088888888889,64.42222222222222,88.2088888888889,66.89999999999999,88.2088888888889,63.431111111111115,178.4 +88.25833333333333,64.45833333333333,88.25833333333333,66.9375,88.25833333333333,63.46666666666667,178.5 +88.30777777777777,64.49444444444444,88.30777777777777,66.975,88.30777777777777,63.50222222222222,178.60000000000002 +88.35722222222222,64.53055555555555,88.35722222222222,67.0125,88.35722222222222,63.53777777777778,178.70000000000002 +88.40666666666667,64.56666666666666,88.40666666666667,67.05,88.40666666666667,63.57333333333333,178.8 +88.45611111111111,64.60277777777777,88.45611111111111,67.08749999999999,88.45611111111111,63.60888888888889,178.9 +88.50555555555556,64.63888888888889,88.50555555555556,67.125,88.50555555555556,63.644444444444446,179.0 +88.55499999999999,64.675,88.55499999999999,67.1625,88.55499999999999,63.68,179.10000000000002 +88.60444444444444,64.71111111111111,88.60444444444444,67.2,88.60444444444444,63.715555555555554,179.20000000000002 +88.65388888888889,64.74722222222222,88.65388888888889,67.2375,88.65388888888889,63.75111111111111,179.3 +88.70333333333333,64.78333333333333,88.70333333333333,67.27499999999999,88.70333333333333,63.78666666666667,179.4 +88.75277777777778,64.81944444444444,88.75277777777778,67.3125,88.75277777777778,63.82222222222222,179.5 +88.80222222222223,64.85555555555555,88.80222222222223,67.35,88.80222222222223,63.85777777777778,179.60000000000002 +88.85166666666666,64.89166666666667,88.85166666666666,67.3875,88.85166666666666,63.89333333333333,179.70000000000002 +88.9011111111111,64.92777777777778,88.9011111111111,67.425,88.9011111111111,63.92888888888889,179.8 +88.95055555555555,64.96388888888889,88.95055555555555,67.46249999999999,88.95055555555555,63.964444444444446,179.9 +89.0,65.0,89.0,67.5,89.0,64.0,180.0 +89.04944444444445,65.03611111111111,89.04944444444445,67.5375,89.04944444444445,64.03555555555556,180.10000000000002 +89.0988888888889,65.07222222222222,89.0988888888889,67.575,89.0988888888889,64.07111111111111,180.20000000000002 +89.14833333333333,65.10833333333333,89.14833333333333,67.6125,89.14833333333333,64.10666666666667,180.3 +89.19777777777777,65.14444444444443,89.19777777777777,67.64999999999999,89.19777777777777,64.14222222222222,180.4 +89.24722222222222,65.18055555555554,89.24722222222222,67.6875,89.24722222222222,64.17777777777778,180.5 +89.29666666666667,65.21666666666665,89.29666666666667,67.725,89.29666666666667,64.21333333333334,180.60000000000002 +89.34611111111111,65.25277777777777,89.34611111111111,67.7625,89.34611111111111,64.24888888888889,180.70000000000002 +89.39555555555556,65.28888888888888,89.39555555555556,67.8,89.39555555555556,64.28444444444445,180.8 +89.445,65.32499999999999,89.445,67.83749999999999,89.445,64.32,180.9 +89.49444444444444,65.3611111111111,89.49444444444444,67.875,89.49444444444444,64.35555555555555,181.0 +89.54388888888889,65.39722222222221,89.54388888888889,67.9125,89.54388888888889,64.39111111111112,181.10000000000002 +89.59333333333333,65.43333333333332,89.59333333333333,67.95,89.59333333333333,64.42666666666666,181.20000000000002 +89.64277777777778,65.46944444444443,89.64277777777778,67.9875,89.64277777777778,64.46222222222222,181.3 +89.69222222222223,65.50555555555555,89.69222222222223,68.02499999999999,89.69222222222223,64.49777777777778,181.4 +89.74166666666666,65.54166666666666,89.74166666666666,68.0625,89.74166666666666,64.53333333333333,181.5 +89.7911111111111,65.57777777777777,89.7911111111111,68.1,89.7911111111111,64.56888888888889,181.60000000000002 +89.84055555555555,65.61388888888888,89.84055555555555,68.1375,89.84055555555555,64.60444444444444,181.70000000000002 +89.89,65.64999999999999,89.89,68.175,89.89,64.64,181.8 +89.93944444444445,65.6861111111111,89.93944444444445,68.21249999999999,89.93944444444445,64.67555555555556,181.9 +89.9888888888889,65.72222222222221,89.9888888888889,68.25,89.9888888888889,64.71111111111111,182.0 +90.03833333333333,65.75833333333333,90.03833333333333,68.2875,90.03833333333333,64.74666666666667,182.10000000000002 +90.08777777777777,65.79444444444444,90.08777777777777,68.325,90.08777777777777,64.78222222222222,182.20000000000002 +90.13722222222222,65.83055555555555,90.13722222222222,68.3625,90.13722222222222,64.81777777777778,182.3 +90.18666666666667,65.86666666666666,90.18666666666667,68.39999999999999,90.18666666666667,64.85333333333334,182.4 +90.23611111111111,65.90277777777777,90.23611111111111,68.4375,90.23611111111111,64.88888888888889,182.5 +90.28555555555556,65.93888888888888,90.28555555555556,68.475,90.28555555555556,64.92444444444445,182.60000000000002 +90.335,65.975,90.335,68.5125,90.335,64.96,182.70000000000002 +90.38444444444444,66.0111111111111,90.38444444444444,68.55,90.38444444444444,64.99555555555555,182.8 +90.43388888888889,66.04722222222222,90.43388888888889,68.58749999999999,90.43388888888889,65.03111111111112,182.9 +90.48333333333333,66.08333333333333,90.48333333333333,68.625,90.48333333333333,65.06666666666666,183.0 +90.53277777777778,66.11944444444444,90.53277777777778,68.6625,90.53277777777778,65.10222222222222,183.10000000000002 +90.58222222222221,66.15555555555555,90.58222222222221,68.7,90.58222222222221,65.13777777777777,183.20000000000002 +90.63166666666666,66.19166666666666,90.63166666666666,68.7375,90.63166666666666,65.17333333333333,183.3 +90.68111111111111,66.22777777777777,90.68111111111111,68.77499999999999,90.68111111111111,65.2088888888889,183.4 +90.73055555555555,66.26388888888889,90.73055555555555,68.8125,90.73055555555555,65.24444444444444,183.5 +90.78,66.3,90.78,68.85,90.78,65.28,183.60000000000002 +90.82944444444445,66.33611111111111,90.82944444444445,68.8875,90.82944444444445,65.31555555555556,183.70000000000002 +90.87888888888888,66.37222222222222,90.87888888888888,68.925,90.87888888888888,65.35111111111111,183.8 +90.92833333333333,66.40833333333333,90.92833333333333,68.96249999999999,90.92833333333333,65.38666666666667,183.9 +90.97777777777777,66.44444444444444,90.97777777777777,69.0,90.97777777777777,65.42222222222222,184.0 +91.02722222222222,66.48055555555555,91.02722222222222,69.0375,91.02722222222222,65.45777777777778,184.10000000000002 +91.07666666666667,66.51666666666667,91.07666666666667,69.075,91.07666666666667,65.49333333333334,184.20000000000002 +91.12611111111111,66.55277777777778,91.12611111111111,69.1125,91.12611111111111,65.52888888888889,184.3 +91.17555555555555,66.58888888888889,91.17555555555555,69.14999999999999,91.17555555555555,65.56444444444445,184.4 +91.225,66.625,91.225,69.1875,91.225,65.6,184.5 +91.27444444444444,66.66111111111111,91.27444444444444,69.225,91.27444444444444,65.63555555555556,184.60000000000002 +91.32388888888889,66.69722222222222,91.32388888888889,69.2625,91.32388888888889,65.67111111111112,184.70000000000002 +91.37333333333333,66.73333333333332,91.37333333333333,69.3,91.37333333333333,65.70666666666666,184.8 +91.42277777777778,66.76944444444443,91.42277777777778,69.33749999999999,91.42277777777778,65.74222222222222,184.9 +91.47222222222221,66.80555555555554,91.47222222222221,69.375,91.47222222222221,65.77777777777777,185.0 +91.52166666666666,66.84166666666665,91.52166666666666,69.4125,91.52166666666666,65.81333333333333,185.10000000000002 +91.57111111111111,66.87777777777777,91.57111111111111,69.45,91.57111111111111,65.8488888888889,185.20000000000002 +91.62055555555555,66.91388888888888,91.62055555555555,69.4875,91.62055555555555,65.88444444444444,185.3 +91.67,66.94999999999999,91.67,69.52499999999999,91.67,65.92,185.4 +91.71944444444445,66.9861111111111,91.71944444444445,69.5625,91.71944444444445,65.95555555555555,185.5 +91.76888888888888,67.02222222222221,91.76888888888888,69.6,91.76888888888888,65.99111111111111,185.60000000000002 +91.81833333333333,67.05833333333332,91.81833333333333,69.6375,91.81833333333333,66.02666666666667,185.70000000000002 +91.86777777777777,67.09444444444443,91.86777777777777,69.675,91.86777777777777,66.06222222222222,185.8 +91.91722222222222,67.13055555555555,91.91722222222222,69.71249999999999,91.91722222222222,66.09777777777778,185.9 +91.96666666666667,67.16666666666666,91.96666666666667,69.75,91.96666666666667,66.13333333333334,186.0 +92.01611111111112,67.20277777777777,92.01611111111112,69.7875,92.01611111111112,66.16888888888889,186.10000000000002 +92.06555555555555,67.23888888888888,92.06555555555555,69.825,92.06555555555555,66.20444444444445,186.20000000000002 +92.115,67.27499999999999,92.115,69.8625,92.115,66.24,186.3 +92.16444444444444,67.3111111111111,92.16444444444444,69.89999999999999,92.16444444444444,66.27555555555556,186.4 +92.21388888888889,67.34722222222221,92.21388888888889,69.9375,92.21388888888889,66.31111111111112,186.5 +92.26333333333334,67.38333333333333,92.26333333333334,69.975,92.26333333333334,66.34666666666666,186.60000000000002 +92.31277777777778,67.41944444444444,92.31277777777778,70.0125,92.31277777777778,66.38222222222223,186.70000000000002 +92.36222222222221,67.45555555555555,92.36222222222221,70.05,92.36222222222221,66.41777777777777,186.8 +92.41166666666666,67.49166666666666,92.41166666666666,70.08749999999999,92.41166666666666,66.45333333333333,186.9 +92.46111111111111,67.52777777777777,92.46111111111111,70.125,92.46111111111111,66.4888888888889,187.0 +92.51055555555556,67.56388888888888,92.51055555555556,70.1625,92.51055555555556,66.52444444444444,187.10000000000002 +92.56,67.6,92.56,70.2,92.56,66.56,187.20000000000002 +92.60944444444445,67.6361111111111,92.60944444444445,70.2375,92.60944444444445,66.59555555555555,187.3 +92.65888888888888,67.67222222222222,92.65888888888888,70.27499999999999,92.65888888888888,66.63111111111111,187.4 +92.70833333333333,67.70833333333333,92.70833333333333,70.3125,92.70833333333333,66.66666666666667,187.5 +92.75777777777778,67.74444444444444,92.75777777777778,70.35,92.75777777777778,66.70222222222222,187.60000000000002 +92.80722222222222,67.78055555555555,92.80722222222222,70.3875,92.80722222222222,66.73777777777778,187.70000000000002 +92.85666666666667,67.81666666666666,92.85666666666667,70.425,92.85666666666667,66.77333333333333,187.8 +92.90611111111112,67.85277777777777,92.90611111111112,70.46249999999999,92.90611111111112,66.80888888888889,187.9 +92.95555555555555,67.88888888888889,92.95555555555555,70.5,92.95555555555555,66.84444444444445,188.0 +93.005,67.925,93.005,70.5375,93.005,66.88,188.10000000000002 +93.05444444444444,67.96111111111111,93.05444444444444,70.575,93.05444444444444,66.91555555555556,188.20000000000002 +93.10388888888889,67.99722222222222,93.10388888888889,70.6125,93.10388888888889,66.95111111111112,188.3 +93.15333333333334,68.03333333333333,93.15333333333334,70.64999999999999,93.15333333333334,66.98666666666666,188.4 +93.20277777777778,68.06944444444444,93.20277777777778,70.6875,93.20277777777778,67.02222222222223,188.5 +93.25222222222222,68.10555555555555,93.25222222222222,70.725,93.25222222222222,67.05777777777777,188.60000000000002 +93.30166666666666,68.14166666666667,93.30166666666666,70.7625,93.30166666666666,67.09333333333333,188.70000000000002 +93.35111111111111,68.17777777777778,93.35111111111111,70.8,93.35111111111111,67.1288888888889,188.8 +93.40055555555556,68.21388888888889,93.40055555555556,70.83749999999999,93.40055555555556,67.16444444444444,188.9 +93.45,68.25,93.45,70.875,93.45,67.2,189.0 +93.49944444444445,68.28611111111111,93.49944444444445,70.9125,93.49944444444445,67.23555555555555,189.10000000000002 +93.54888888888888,68.32222222222222,93.54888888888888,70.95,93.54888888888888,67.27111111111111,189.20000000000002 +93.59833333333333,68.35833333333332,93.59833333333333,70.9875,93.59833333333333,67.30666666666667,189.3 +93.64777777777778,68.39444444444443,93.64777777777778,71.02499999999999,93.64777777777778,67.34222222222222,189.4 +93.69722222222222,68.43055555555554,93.69722222222222,71.0625,93.69722222222222,67.37777777777778,189.5 +93.74666666666667,68.46666666666665,93.74666666666667,71.1,93.74666666666667,67.41333333333333,189.60000000000002 +93.79611111111112,68.50277777777777,93.79611111111112,71.1375,93.79611111111112,67.44888888888889,189.70000000000002 +93.84555555555555,68.53888888888888,93.84555555555555,71.175,93.84555555555555,67.48444444444445,189.8 +93.895,68.57499999999999,93.895,71.21249999999999,93.895,67.52,189.9 +93.94444444444444,68.6111111111111,93.94444444444444,71.25,93.94444444444444,67.55555555555556,190.0 +93.99388888888889,68.64722222222221,93.99388888888889,71.2875,93.99388888888889,67.5911111111111,190.10000000000002 +94.04333333333334,68.68333333333332,94.04333333333334,71.325,94.04333333333334,67.62666666666667,190.20000000000002 +94.09277777777777,68.71944444444443,94.09277777777777,71.3625,94.09277777777777,67.66222222222223,190.3 +94.14222222222222,68.75555555555555,94.14222222222222,71.39999999999999,94.14222222222222,67.69777777777777,190.4 +94.19166666666666,68.79166666666666,94.19166666666666,71.4375,94.19166666666666,67.73333333333333,190.5 +94.24111111111111,68.82777777777777,94.24111111111111,71.475,94.24111111111111,67.7688888888889,190.60000000000002 +94.29055555555556,68.86388888888888,94.29055555555556,71.5125,94.29055555555556,67.80444444444444,190.70000000000002 +94.34,68.89999999999999,94.34,71.55,94.34,67.84,190.8 +94.38944444444444,68.9361111111111,94.38944444444444,71.58749999999999,94.38944444444444,67.87555555555555,190.9 +94.43888888888888,68.97222222222221,94.43888888888888,71.625,94.43888888888888,67.91111111111111,191.0 +94.48833333333333,69.00833333333333,94.48833333333333,71.6625,94.48833333333333,67.94666666666667,191.10000000000002 +94.53777777777778,69.04444444444444,94.53777777777778,71.7,94.53777777777778,67.98222222222222,191.20000000000002 +94.58722222222222,69.08055555555555,94.58722222222222,71.7375,94.58722222222222,68.01777777777778,191.3 +94.63666666666667,69.11666666666666,94.63666666666667,71.77499999999999,94.63666666666667,68.05333333333333,191.4 +94.6861111111111,69.15277777777777,94.6861111111111,71.8125,94.6861111111111,68.08888888888889,191.5 +94.73555555555555,69.18888888888888,94.73555555555555,71.85,94.73555555555555,68.12444444444445,191.60000000000002 +94.785,69.225,94.785,71.8875,94.785,68.16,191.70000000000002 +94.83444444444444,69.2611111111111,94.83444444444444,71.925,94.83444444444444,68.19555555555556,191.8 +94.88388888888889,69.29722222222222,94.88388888888889,71.96249999999999,94.88388888888889,68.2311111111111,191.9 +94.93333333333334,69.33333333333333,94.93333333333334,72.0,94.93333333333334,68.26666666666667,192.0 +94.98277777777777,69.36944444444444,94.98277777777777,72.0375,94.98277777777777,68.30222222222223,192.10000000000002 +95.03222222222222,69.40555555555555,95.03222222222222,72.075,95.03222222222222,68.33777777777777,192.20000000000002 +95.08166666666666,69.44166666666666,95.08166666666666,72.1125,95.08166666666666,68.37333333333333,192.3 +95.13111111111111,69.47777777777777,95.13111111111111,72.14999999999999,95.13111111111111,68.40888888888888,192.4 +95.18055555555556,69.51388888888889,95.18055555555556,72.1875,95.18055555555556,68.44444444444444,192.5 +95.23,69.55,95.23,72.225,95.23,68.48,192.60000000000002 +95.27944444444444,69.58611111111111,95.27944444444444,72.2625,95.27944444444444,68.51555555555555,192.70000000000002 +95.32888888888888,69.62222222222222,95.32888888888888,72.3,95.32888888888888,68.55111111111111,192.8 +95.37833333333333,69.65833333333333,95.37833333333333,72.33749999999999,95.37833333333333,68.58666666666667,192.9 +95.42777777777778,69.69444444444444,95.42777777777778,72.375,95.42777777777778,68.62222222222222,193.0 +95.47722222222222,69.73055555555555,95.47722222222222,72.4125,95.47722222222222,68.65777777777778,193.10000000000002 +95.52666666666667,69.76666666666667,95.52666666666667,72.45,95.52666666666667,68.69333333333333,193.20000000000002 +95.5761111111111,69.80277777777778,95.5761111111111,72.4875,95.5761111111111,68.72888888888889,193.3 +95.62555555555555,69.83888888888889,95.62555555555555,72.52499999999999,95.62555555555555,68.76444444444445,193.4 +95.675,69.875,95.675,72.5625,95.675,68.8,193.5 +95.72444444444444,69.91111111111111,95.72444444444444,72.6,95.72444444444444,68.83555555555556,193.60000000000002 +95.77388888888889,69.94722222222221,95.77388888888889,72.6375,95.77388888888889,68.8711111111111,193.70000000000002 +95.82333333333334,69.98333333333332,95.82333333333334,72.675,95.82333333333334,68.90666666666667,193.8 +95.87277777777777,70.01944444444443,95.87277777777777,72.71249999999999,95.87277777777777,68.94222222222223,193.9 +95.92222222222222,70.05555555555554,95.92222222222222,72.75,95.92222222222222,68.97777777777777,194.0 +95.97166666666666,70.09166666666665,95.97166666666666,72.7875,95.97166666666666,69.01333333333334,194.10000000000002 +96.02111111111111,70.12777777777777,96.02111111111111,72.825,96.02111111111111,69.04888888888888,194.20000000000002 +96.07055555555556,70.16388888888888,96.07055555555556,72.8625,96.07055555555556,69.08444444444444,194.3 +96.12,70.19999999999999,96.12,72.89999999999999,96.12,69.12,194.4 +96.16944444444444,70.2361111111111,96.16944444444444,72.9375,96.16944444444444,69.15555555555555,194.5 +96.21888888888888,70.27222222222221,96.21888888888888,72.975,96.21888888888888,69.19111111111111,194.60000000000002 +96.26833333333333,70.30833333333332,96.26833333333333,73.0125,96.26833333333333,69.22666666666667,194.70000000000002 +96.31777777777778,70.34444444444443,96.31777777777778,73.05,96.31777777777778,69.26222222222222,194.8 +96.36722222222222,70.38055555555555,96.36722222222222,73.08749999999999,96.36722222222222,69.29777777777778,194.9 +96.41666666666667,70.41666666666666,96.41666666666667,73.125,96.41666666666667,69.33333333333333,195.0 +96.4661111111111,70.45277777777777,96.4661111111111,73.1625,96.4661111111111,69.36888888888889,195.10000000000002 +96.51555555555555,70.48888888888888,96.51555555555555,73.2,96.51555555555555,69.40444444444445,195.20000000000002 +96.565,70.52499999999999,96.565,73.2375,96.565,69.44,195.3 +96.61444444444444,70.5611111111111,96.61444444444444,73.27499999999999,96.61444444444444,69.47555555555556,195.4 +96.66388888888889,70.59722222222221,96.66388888888889,73.3125,96.66388888888889,69.5111111111111,195.5 +96.71333333333334,70.63333333333333,96.71333333333334,73.35,96.71333333333334,69.54666666666667,195.60000000000002 +96.76277777777777,70.66944444444444,96.76277777777777,73.3875,96.76277777777777,69.58222222222223,195.70000000000002 +96.81222222222222,70.70555555555555,96.81222222222222,73.425,96.81222222222222,69.61777777777777,195.8 +96.86166666666666,70.74166666666666,96.86166666666666,73.46249999999999,96.86166666666666,69.65333333333334,195.9 +96.91111111111111,70.77777777777777,96.91111111111111,73.5,96.91111111111111,69.68888888888888,196.0 +96.96055555555556,70.81388888888888,96.96055555555556,73.5375,96.96055555555556,69.72444444444444,196.10000000000002 +97.01,70.85,97.01,73.575,97.01,69.76,196.20000000000002 +97.05944444444444,70.8861111111111,97.05944444444444,73.6125,97.05944444444444,69.79555555555555,196.3 +97.10888888888888,70.92222222222222,97.10888888888888,73.64999999999999,97.10888888888888,69.83111111111111,196.4 +97.15833333333333,70.95833333333333,97.15833333333333,73.6875,97.15833333333333,69.86666666666666,196.5 +97.20777777777778,70.99444444444444,97.20777777777778,73.725,97.20777777777778,69.90222222222222,196.60000000000002 +97.25722222222223,71.03055555555555,97.25722222222223,73.7625,97.25722222222223,69.93777777777778,196.70000000000002 +97.30666666666667,71.06666666666666,97.30666666666667,73.8,97.30666666666667,69.97333333333333,196.8 +97.3561111111111,71.10277777777777,97.3561111111111,73.83749999999999,97.3561111111111,70.00888888888889,196.9 +97.40555555555555,71.13888888888889,97.40555555555555,73.875,97.40555555555555,70.04444444444445,197.0 +97.455,71.175,97.455,73.9125,97.455,70.08,197.10000000000002 +97.50444444444445,71.21111111111111,97.50444444444445,73.95,97.50444444444445,70.11555555555556,197.20000000000002 +97.55388888888889,71.24722222222222,97.55388888888889,73.9875,97.55388888888889,70.1511111111111,197.3 +97.60333333333334,71.28333333333333,97.60333333333334,74.02499999999999,97.60333333333334,70.18666666666667,197.4 +97.65277777777777,71.31944444444444,97.65277777777777,74.0625,97.65277777777777,70.22222222222223,197.5 +97.70222222222222,71.35555555555555,97.70222222222222,74.1,97.70222222222222,70.25777777777778,197.60000000000002 +97.75166666666667,71.39166666666667,97.75166666666667,74.1375,97.75166666666667,70.29333333333334,197.70000000000002 +97.80111111111111,71.42777777777778,97.80111111111111,74.175,97.80111111111111,70.32888888888888,197.8 +97.85055555555556,71.46388888888889,97.85055555555556,74.21249999999999,97.85055555555556,70.36444444444444,197.9 +97.89999999999999,71.5,97.89999999999999,74.25,97.89999999999999,70.4,198.0 +97.94944444444444,71.53611111111111,97.94944444444444,74.2875,97.94944444444444,70.43555555555555,198.10000000000002 +97.99888888888889,71.57222222222221,97.99888888888889,74.325,97.99888888888889,70.47111111111111,198.20000000000002 +98.04833333333333,71.60833333333332,98.04833333333333,74.3625,98.04833333333333,70.50666666666666,198.3 +98.09777777777778,71.64444444444443,98.09777777777778,74.39999999999999,98.09777777777778,70.54222222222222,198.4 +98.14722222222223,71.68055555555554,98.14722222222223,74.4375,98.14722222222223,70.57777777777778,198.5 +98.19666666666666,71.71666666666665,98.19666666666666,74.475,98.19666666666666,70.61333333333333,198.60000000000002 +98.2461111111111,71.75277777777777,98.2461111111111,74.5125,98.2461111111111,70.64888888888889,198.70000000000002 +98.29555555555555,71.78888888888888,98.29555555555555,74.55,98.29555555555555,70.68444444444444,198.8 +98.345,71.82499999999999,98.345,74.58749999999999,98.345,70.72,198.9 +98.39444444444445,71.8611111111111,98.39444444444445,74.625,98.39444444444445,70.75555555555556,199.0 +98.44388888888889,71.89722222222221,98.44388888888889,74.6625,98.44388888888889,70.7911111111111,199.10000000000002 +98.49333333333333,71.93333333333332,98.49333333333333,74.7,98.49333333333333,70.82666666666667,199.20000000000002 +98.54277777777777,71.96944444444443,98.54277777777777,74.7375,98.54277777777777,70.86222222222223,199.3 +98.59222222222222,72.00555555555555,98.59222222222222,74.77499999999999,98.59222222222222,70.89777777777778,199.4 +98.64166666666667,72.04166666666666,98.64166666666667,74.8125,98.64166666666667,70.93333333333334,199.5 +98.69111111111111,72.07777777777777,98.69111111111111,74.85,98.69111111111111,70.96888888888888,199.60000000000002 +98.74055555555556,72.11388888888888,98.74055555555556,74.8875,98.74055555555556,71.00444444444445,199.70000000000002 +98.78999999999999,72.14999999999999,98.78999999999999,74.925,98.78999999999999,71.04,199.8 +98.83944444444444,72.1861111111111,98.83944444444444,74.96249999999999,98.83944444444444,71.07555555555555,199.9 +98.88888888888889,72.22222222222221,98.88888888888889,75.0,98.88888888888889,71.11111111111111,200.0 +98.93833333333333,72.25833333333333,98.93833333333333,75.0375,98.93833333333333,71.14666666666666,200.10000000000002 +98.98777777777778,72.29444444444444,98.98777777777778,75.075,98.98777777777778,71.18222222222222,200.20000000000002 +99.03722222222223,72.33055555555555,99.03722222222223,75.1125,99.03722222222223,71.21777777777778,200.3 +99.08666666666666,72.36666666666666,99.08666666666666,75.14999999999999,99.08666666666666,71.25333333333333,200.4 +99.1361111111111,72.40277777777777,99.1361111111111,75.1875,99.1361111111111,71.28888888888889,200.5 +99.18555555555555,72.43888888888888,99.18555555555555,75.225,99.18555555555555,71.32444444444444,200.60000000000002 +99.235,72.475,99.235,75.2625,99.235,71.36,200.70000000000002 +99.28444444444445,72.5111111111111,99.28444444444445,75.3,99.28444444444445,71.39555555555556,200.8 +99.3338888888889,72.54722222222222,99.3338888888889,75.33749999999999,99.3338888888889,71.43111111111111,200.9 +99.38333333333333,72.58333333333333,99.38333333333333,75.375,99.38333333333333,71.46666666666667,201.0 +99.43277777777777,72.61944444444444,99.43277777777777,75.4125,99.43277777777777,71.50222222222222,201.10000000000002 +99.48222222222222,72.65555555555555,99.48222222222222,75.45,99.48222222222222,71.53777777777778,201.20000000000002 +99.53166666666667,72.69166666666666,99.53166666666667,75.4875,99.53166666666667,71.57333333333334,201.3 +99.58111111111111,72.72777777777777,99.58111111111111,75.52499999999999,99.58111111111111,71.60888888888888,201.4 +99.63055555555556,72.76388888888889,99.63055555555556,75.5625,99.63055555555556,71.64444444444445,201.5 +99.67999999999999,72.8,99.67999999999999,75.6,99.67999999999999,71.68,201.60000000000002 +99.72944444444444,72.83611111111111,99.72944444444444,75.6375,99.72944444444444,71.71555555555555,201.70000000000002 +99.77888888888889,72.87222222222222,99.77888888888889,75.675,99.77888888888889,71.75111111111111,201.8 +99.82833333333333,72.90833333333333,99.82833333333333,75.71249999999999,99.82833333333333,71.78666666666666,201.9 +99.87777777777778,72.94444444444444,99.87777777777778,75.75,99.87777777777778,71.82222222222222,202.0 +99.92722222222223,72.98055555555555,99.92722222222223,75.7875,99.92722222222223,71.85777777777778,202.10000000000002 +99.97666666666666,73.01666666666667,99.97666666666666,75.825,99.97666666666666,71.89333333333333,202.20000000000002 +100.0261111111111,73.05277777777778,100.0261111111111,75.8625,100.0261111111111,71.92888888888889,202.3 +100.07555555555555,73.08888888888889,100.07555555555555,75.89999999999999,100.07555555555555,71.96444444444444,202.4 +100.125,73.125,100.125,75.9375,100.125,72.0,202.5 +100.17444444444445,73.1611111111111,100.17444444444445,75.975,100.17444444444445,72.03555555555556,202.60000000000002 +100.2238888888889,73.19722222222221,100.2238888888889,76.0125,100.2238888888889,72.07111111111111,202.70000000000002 +100.27333333333333,73.23333333333332,100.27333333333333,76.05,100.27333333333333,72.10666666666667,202.8 +100.32277777777777,73.26944444444443,100.32277777777777,76.08749999999999,100.32277777777777,72.14222222222222,202.9 +100.37222222222222,73.30555555555554,100.37222222222222,76.125,100.37222222222222,72.17777777777778,203.0 +100.42166666666667,73.34166666666665,100.42166666666667,76.1625,100.42166666666667,72.21333333333334,203.10000000000002 +100.47111111111111,73.37777777777777,100.47111111111111,76.2,100.47111111111111,72.24888888888889,203.20000000000002 +100.52055555555556,73.41388888888888,100.52055555555556,76.2375,100.52055555555556,72.28444444444445,203.3 +100.57,73.44999999999999,100.57,76.27499999999999,100.57,72.32,203.4 +100.61944444444444,73.4861111111111,100.61944444444444,76.3125,100.61944444444444,72.35555555555555,203.5 +100.66888888888889,73.52222222222221,100.66888888888889,76.35,100.66888888888889,72.39111111111112,203.60000000000002 +100.71833333333333,73.55833333333332,100.71833333333333,76.3875,100.71833333333333,72.42666666666666,203.70000000000002 +100.76777777777778,73.59444444444443,100.76777777777778,76.425,100.76777777777778,72.46222222222222,203.8 +100.81722222222223,73.63055555555555,100.81722222222223,76.46249999999999,100.81722222222223,72.49777777777778,203.9 +100.86666666666666,73.66666666666666,100.86666666666666,76.5,100.86666666666666,72.53333333333333,204.0 +100.9161111111111,73.70277777777777,100.9161111111111,76.5375,100.9161111111111,72.56888888888889,204.10000000000002 +100.96555555555555,73.73888888888888,100.96555555555555,76.575,100.96555555555555,72.60444444444444,204.20000000000002 +101.015,73.77499999999999,101.015,76.6125,101.015,72.64,204.3 +101.06444444444445,73.8111111111111,101.06444444444445,76.64999999999999,101.06444444444445,72.67555555555556,204.4 +101.1138888888889,73.84722222222221,101.1138888888889,76.6875,101.1138888888889,72.71111111111111,204.5 +101.16333333333333,73.88333333333333,101.16333333333333,76.725,101.16333333333333,72.74666666666667,204.60000000000002 +101.21277777777777,73.91944444444444,101.21277777777777,76.7625,101.21277777777777,72.78222222222222,204.70000000000002 +101.26222222222222,73.95555555555555,101.26222222222222,76.8,101.26222222222222,72.81777777777778,204.8 +101.31166666666667,73.99166666666666,101.31166666666667,76.83749999999999,101.31166666666667,72.85333333333334,204.9 +101.36111111111111,74.02777777777777,101.36111111111111,76.875,101.36111111111111,72.88888888888889,205.0 +101.41055555555555,74.06388888888888,101.41055555555555,76.9125,101.41055555555555,72.92444444444445,205.10000000000002 +101.46,74.1,101.46,76.95,101.46,72.96,205.20000000000002 +101.50944444444444,74.1361111111111,101.50944444444444,76.9875,101.50944444444444,72.99555555555555,205.3 +101.55888888888889,74.17222222222222,101.55888888888889,77.02499999999999,101.55888888888889,73.03111111111112,205.4 +101.60833333333333,74.20833333333333,101.60833333333333,77.0625,101.60833333333333,73.06666666666666,205.5 +101.65777777777778,74.24444444444444,101.65777777777778,77.1,101.65777777777778,73.10222222222222,205.60000000000002 +101.70722222222221,74.28055555555555,101.70722222222221,77.1375,101.70722222222221,73.13777777777777,205.70000000000002 +101.75666666666666,74.31666666666666,101.75666666666666,77.175,101.75666666666666,73.17333333333333,205.8 +101.80611111111111,74.35277777777777,101.80611111111111,77.21249999999999,101.80611111111111,73.2088888888889,205.9 +101.85555555555555,74.38888888888889,101.85555555555555,77.25,101.85555555555555,73.24444444444444,206.0 +101.905,74.425,101.905,77.2875,101.905,73.28,206.10000000000002 +101.95444444444445,74.46111111111111,101.95444444444445,77.325,101.95444444444445,73.31555555555556,206.20000000000002 +102.00388888888888,74.49722222222222,102.00388888888888,77.3625,102.00388888888888,73.35111111111111,206.3 +102.05333333333333,74.53333333333333,102.05333333333333,77.39999999999999,102.05333333333333,73.38666666666667,206.4 +102.10277777777777,74.56944444444444,102.10277777777777,77.4375,102.10277777777777,73.42222222222222,206.5 +102.15222222222222,74.60555555555555,102.15222222222222,77.475,102.15222222222222,73.45777777777778,206.60000000000002 +102.20166666666667,74.64166666666667,102.20166666666667,77.5125,102.20166666666667,73.49333333333334,206.70000000000002 +102.25111111111111,74.67777777777778,102.25111111111111,77.55,102.25111111111111,73.52888888888889,206.8 +102.30055555555555,74.71388888888889,102.30055555555555,77.58749999999999,102.30055555555555,73.56444444444445,206.9 +102.35,74.75,102.35,77.625,102.35,73.6,207.0 +102.39944444444444,74.7861111111111,102.39944444444444,77.6625,102.39944444444444,73.63555555555556,207.10000000000002 +102.44888888888889,74.82222222222221,102.44888888888889,77.7,102.44888888888889,73.67111111111112,207.20000000000002 +102.49833333333333,74.85833333333332,102.49833333333333,77.7375,102.49833333333333,73.70666666666666,207.3 +102.54777777777778,74.89444444444443,102.54777777777778,77.77499999999999,102.54777777777778,73.74222222222222,207.4 +102.59722222222221,74.93055555555554,102.59722222222221,77.8125,102.59722222222221,73.77777777777777,207.5 +102.64666666666666,74.96666666666665,102.64666666666666,77.85,102.64666666666666,73.81333333333333,207.60000000000002 +102.69611111111111,75.00277777777777,102.69611111111111,77.8875,102.69611111111111,73.8488888888889,207.70000000000002 +102.74555555555555,75.03888888888888,102.74555555555555,77.925,102.74555555555555,73.88444444444444,207.8 +102.795,75.07499999999999,102.795,77.96249999999999,102.795,73.92,207.9 +102.84444444444445,75.1111111111111,102.84444444444445,78.0,102.84444444444445,73.95555555555555,208.0 +102.89388888888888,75.14722222222221,102.89388888888888,78.0375,102.89388888888888,73.99111111111111,208.10000000000002 +102.94333333333333,75.18333333333332,102.94333333333333,78.075,102.94333333333333,74.02666666666667,208.20000000000002 +102.99277777777777,75.21944444444443,102.99277777777777,78.1125,102.99277777777777,74.06222222222222,208.3 +103.04222222222222,75.25555555555555,103.04222222222222,78.14999999999999,103.04222222222222,74.09777777777778,208.4 +103.09166666666667,75.29166666666666,103.09166666666667,78.1875,103.09166666666667,74.13333333333334,208.5 +103.14111111111112,75.32777777777777,103.14111111111112,78.225,103.14111111111112,74.16888888888889,208.60000000000002 +103.19055555555555,75.36388888888888,103.19055555555555,78.2625,103.19055555555555,74.20444444444445,208.70000000000002 +103.24,75.39999999999999,103.24,78.3,103.24,74.24,208.8 +103.28944444444444,75.4361111111111,103.28944444444444,78.33749999999999,103.28944444444444,74.27555555555556,208.9 +103.33888888888889,75.47222222222221,103.33888888888889,78.375,103.33888888888889,74.31111111111112,209.0 +103.38833333333334,75.50833333333333,103.38833333333334,78.4125,103.38833333333334,74.34666666666666,209.10000000000002 +103.43777777777778,75.54444444444444,103.43777777777778,78.45,103.43777777777778,74.38222222222223,209.20000000000002 +103.48722222222221,75.58055555555555,103.48722222222221,78.4875,103.48722222222221,74.41777777777777,209.3 +103.53666666666666,75.61666666666666,103.53666666666666,78.52499999999999,103.53666666666666,74.45333333333333,209.4 +103.58611111111111,75.65277777777777,103.58611111111111,78.5625,103.58611111111111,74.4888888888889,209.5 +103.63555555555556,75.68888888888888,103.63555555555556,78.6,103.63555555555556,74.52444444444444,209.60000000000002 +103.685,75.725,103.685,78.6375,103.685,74.56,209.70000000000002 +103.73444444444445,75.7611111111111,103.73444444444445,78.675,103.73444444444445,74.59555555555555,209.8 +103.78388888888888,75.79722222222222,103.78388888888888,78.71249999999999,103.78388888888888,74.63111111111111,209.9 +103.83333333333333,75.83333333333333,103.83333333333333,78.75,103.83333333333333,74.66666666666667,210.0 +103.88277777777778,75.86944444444444,103.88277777777778,78.7875,103.88277777777778,74.70222222222222,210.10000000000002 +103.93222222222222,75.90555555555555,103.93222222222222,78.825,103.93222222222222,74.73777777777778,210.20000000000002 +103.98166666666667,75.94166666666666,103.98166666666667,78.8625,103.98166666666667,74.77333333333333,210.3 +104.03111111111112,75.97777777777777,104.03111111111112,78.89999999999999,104.03111111111112,74.80888888888889,210.4 +104.08055555555555,76.01388888888889,104.08055555555555,78.9375,104.08055555555555,74.84444444444445,210.5 +104.13,76.05,104.13,78.975,104.13,74.88,210.60000000000002 +104.17944444444444,76.08611111111111,104.17944444444444,79.0125,104.17944444444444,74.91555555555556,210.70000000000002 +104.22888888888889,76.12222222222222,104.22888888888889,79.05,104.22888888888889,74.95111111111112,210.8 +104.27833333333334,76.15833333333333,104.27833333333334,79.08749999999999,104.27833333333334,74.98666666666666,210.9 +104.32777777777778,76.19444444444444,104.32777777777778,79.125,104.32777777777778,75.02222222222223,211.0 +104.37722222222222,76.23055555555555,104.37722222222222,79.1625,104.37722222222222,75.05777777777777,211.10000000000002 +104.42666666666666,76.26666666666667,104.42666666666666,79.2,104.42666666666666,75.09333333333333,211.20000000000002 +104.47611111111111,76.30277777777778,104.47611111111111,79.2375,104.47611111111111,75.1288888888889,211.3 +104.52555555555556,76.33888888888889,104.52555555555556,79.27499999999999,104.52555555555556,75.16444444444444,211.4 +104.575,76.37499999999999,104.575,79.3125,104.575,75.2,211.5 +104.62444444444445,76.4111111111111,104.62444444444445,79.35,104.62444444444445,75.23555555555555,211.60000000000002 +104.67388888888888,76.44722222222221,104.67388888888888,79.3875,104.67388888888888,75.27111111111111,211.70000000000002 +104.72333333333333,76.48333333333332,104.72333333333333,79.425,104.72333333333333,75.30666666666667,211.8 +104.77277777777778,76.51944444444443,104.77277777777778,79.46249999999999,104.77277777777778,75.34222222222222,211.9 +104.82222222222222,76.55555555555554,104.82222222222222,79.5,104.82222222222222,75.37777777777778,212.0 +104.87166666666667,76.59166666666665,104.87166666666667,79.5375,104.87166666666667,75.41333333333333,212.10000000000002 +104.9211111111111,76.62777777777777,104.9211111111111,79.575,104.9211111111111,75.44888888888889,212.20000000000002 +104.97055555555555,76.66388888888888,104.97055555555555,79.6125,104.97055555555555,75.48444444444445,212.3 +105.02,76.69999999999999,105.02,79.64999999999999,105.02,75.52,212.4 +105.06944444444444,76.7361111111111,105.06944444444444,79.6875,105.06944444444444,75.55555555555556,212.5 +105.11888888888889,76.77222222222221,105.11888888888889,79.725,105.11888888888889,75.5911111111111,212.60000000000002 +105.16833333333334,76.80833333333332,105.16833333333334,79.7625,105.16833333333334,75.62666666666667,212.70000000000002 +105.21777777777777,76.84444444444443,105.21777777777777,79.8,105.21777777777777,75.66222222222223,212.8 +105.26722222222222,76.88055555555555,105.26722222222222,79.83749999999999,105.26722222222222,75.69777777777777,212.9 +105.31666666666666,76.91666666666666,105.31666666666666,79.875,105.31666666666666,75.73333333333333,213.0 +105.36611111111111,76.95277777777777,105.36611111111111,79.9125,105.36611111111111,75.7688888888889,213.10000000000002 +105.41555555555556,76.98888888888888,105.41555555555556,79.95,105.41555555555556,75.80444444444444,213.20000000000002 +105.465,77.02499999999999,105.465,79.9875,105.465,75.84,213.3 +105.51444444444444,77.0611111111111,105.51444444444444,80.02499999999999,105.51444444444444,75.87555555555555,213.4 +105.56388888888888,77.09722222222221,105.56388888888888,80.0625,105.56388888888888,75.91111111111111,213.5 +105.61333333333333,77.13333333333333,105.61333333333333,80.1,105.61333333333333,75.94666666666667,213.60000000000002 +105.66277777777778,77.16944444444444,105.66277777777778,80.1375,105.66277777777778,75.98222222222222,213.70000000000002 +105.71222222222222,77.20555555555555,105.71222222222222,80.175,105.71222222222222,76.01777777777778,213.8 +105.76166666666667,77.24166666666666,105.76166666666667,80.21249999999999,105.76166666666667,76.05333333333333,213.9 +105.8111111111111,77.27777777777777,105.8111111111111,80.25,105.8111111111111,76.08888888888889,214.0 +105.86055555555555,77.31388888888888,105.86055555555555,80.2875,105.86055555555555,76.12444444444445,214.10000000000002 +105.91,77.35,105.91,80.325,105.91,76.16,214.20000000000002 +105.95944444444444,77.3861111111111,105.95944444444444,80.3625,105.95944444444444,76.19555555555556,214.3 +106.00888888888889,77.42222222222222,106.00888888888889,80.39999999999999,106.00888888888889,76.2311111111111,214.4 +106.05833333333334,77.45833333333333,106.05833333333334,80.4375,106.05833333333334,76.26666666666667,214.5 +106.10777777777777,77.49444444444444,106.10777777777777,80.475,106.10777777777777,76.30222222222223,214.60000000000002 +106.15722222222222,77.53055555555555,106.15722222222222,80.5125,106.15722222222222,76.33777777777777,214.70000000000002 +106.20666666666666,77.56666666666666,106.20666666666666,80.55,106.20666666666666,76.37333333333333,214.8 +106.25611111111111,77.60277777777777,106.25611111111111,80.58749999999999,106.25611111111111,76.40888888888888,214.9 +106.30555555555556,77.63888888888889,106.30555555555556,80.625,106.30555555555556,76.44444444444444,215.0 +106.355,77.675,106.355,80.6625,106.355,76.48,215.10000000000002 +106.40444444444444,77.71111111111111,106.40444444444444,80.7,106.40444444444444,76.51555555555555,215.20000000000002 +106.45388888888888,77.74722222222222,106.45388888888888,80.7375,106.45388888888888,76.55111111111111,215.3 +106.50333333333333,77.78333333333333,106.50333333333333,80.77499999999999,106.50333333333333,76.58666666666667,215.4 +106.55277777777778,77.81944444444444,106.55277777777778,80.8125,106.55277777777778,76.62222222222222,215.5 +106.60222222222222,77.85555555555555,106.60222222222222,80.85,106.60222222222222,76.65777777777778,215.60000000000002 +106.65166666666667,77.89166666666667,106.65166666666667,80.8875,106.65166666666667,76.69333333333333,215.70000000000002 +106.7011111111111,77.92777777777778,106.7011111111111,80.925,106.7011111111111,76.72888888888889,215.8 +106.75055555555555,77.96388888888889,106.75055555555555,80.96249999999999,106.75055555555555,76.76444444444445,215.9 +106.8,77.99999999999999,106.8,81.0,106.8,76.8,216.0 +106.84944444444444,78.0361111111111,106.84944444444444,81.0375,106.84944444444444,76.83555555555556,216.10000000000002 +106.89888888888889,78.07222222222221,106.89888888888889,81.075,106.89888888888889,76.8711111111111,216.20000000000002 +106.94833333333334,78.10833333333332,106.94833333333334,81.1125,106.94833333333334,76.90666666666667,216.3 +106.99777777777777,78.14444444444443,106.99777777777777,81.14999999999999,106.99777777777777,76.94222222222223,216.4 +107.04722222222222,78.18055555555554,107.04722222222222,81.1875,107.04722222222222,76.97777777777777,216.5 +107.09666666666666,78.21666666666665,107.09666666666666,81.225,107.09666666666666,77.01333333333334,216.60000000000002 +107.14611111111111,78.25277777777777,107.14611111111111,81.2625,107.14611111111111,77.04888888888888,216.70000000000002 +107.19555555555556,78.28888888888888,107.19555555555556,81.3,107.19555555555556,77.08444444444444,216.8 +107.245,78.32499999999999,107.245,81.33749999999999,107.245,77.12,216.9 +107.29444444444444,78.3611111111111,107.29444444444444,81.375,107.29444444444444,77.15555555555555,217.0 +107.34388888888888,78.39722222222221,107.34388888888888,81.4125,107.34388888888888,77.19111111111111,217.10000000000002 +107.39333333333333,78.43333333333332,107.39333333333333,81.45,107.39333333333333,77.22666666666667,217.20000000000002 +107.44277777777778,78.46944444444443,107.44277777777778,81.4875,107.44277777777778,77.26222222222222,217.3 +107.49222222222222,78.50555555555555,107.49222222222222,81.52499999999999,107.49222222222222,77.29777777777778,217.4 +107.54166666666667,78.54166666666666,107.54166666666667,81.5625,107.54166666666667,77.33333333333333,217.5 +107.5911111111111,78.57777777777777,107.5911111111111,81.6,107.5911111111111,77.36888888888889,217.60000000000002 +107.64055555555555,78.61388888888888,107.64055555555555,81.6375,107.64055555555555,77.40444444444445,217.70000000000002 +107.69,78.64999999999999,107.69,81.675,107.69,77.44,217.8 +107.73944444444444,78.6861111111111,107.73944444444444,81.71249999999999,107.73944444444444,77.47555555555556,217.9 +107.78888888888889,78.72222222222221,107.78888888888889,81.75,107.78888888888889,77.5111111111111,218.0 +107.83833333333334,78.75833333333333,107.83833333333334,81.7875,107.83833333333334,77.54666666666667,218.10000000000002 +107.88777777777777,78.79444444444444,107.88777777777777,81.825,107.88777777777777,77.58222222222223,218.20000000000002 +107.93722222222222,78.83055555555555,107.93722222222222,81.8625,107.93722222222222,77.61777777777777,218.3 +107.98666666666666,78.86666666666666,107.98666666666666,81.89999999999999,107.98666666666666,77.65333333333334,218.4 +108.03611111111111,78.90277777777777,108.03611111111111,81.9375,108.03611111111111,77.68888888888888,218.5 +108.08555555555556,78.93888888888888,108.08555555555556,81.975,108.08555555555556,77.72444444444444,218.60000000000002 +108.135,78.975,108.135,82.0125,108.135,77.76,218.70000000000002 +108.18444444444444,79.0111111111111,108.18444444444444,82.05,108.18444444444444,77.79555555555555,218.8 +108.23388888888888,79.04722222222222,108.23388888888888,82.08749999999999,108.23388888888888,77.83111111111111,218.9 +108.28333333333333,79.08333333333333,108.28333333333333,82.125,108.28333333333333,77.86666666666666,219.0 +108.33277777777778,79.11944444444444,108.33277777777778,82.1625,108.33277777777778,77.90222222222222,219.10000000000002 +108.38222222222223,79.15555555555555,108.38222222222223,82.2,108.38222222222223,77.93777777777778,219.20000000000002 +108.43166666666667,79.19166666666666,108.43166666666667,82.2375,108.43166666666667,77.97333333333333,219.3 +108.4811111111111,79.22777777777777,108.4811111111111,82.27499999999999,108.4811111111111,78.00888888888889,219.4 +108.53055555555555,79.26388888888889,108.53055555555555,82.3125,108.53055555555555,78.04444444444445,219.5 +108.58,79.3,108.58,82.35,108.58,78.08,219.60000000000002 +108.62944444444445,79.33611111111111,108.62944444444445,82.3875,108.62944444444445,78.11555555555556,219.70000000000002 +108.67888888888889,79.37222222222222,108.67888888888889,82.425,108.67888888888889,78.1511111111111,219.8 +108.72833333333332,79.40833333333333,108.72833333333332,82.46249999999999,108.72833333333332,78.18666666666667,219.9 +108.77777777777777,79.44444444444444,108.77777777777777,82.5,108.77777777777777,78.22222222222223,220.0 +108.82722222222222,79.48055555555555,108.82722222222222,82.5375,108.82722222222222,78.25777777777778,220.10000000000002 +108.87666666666667,79.51666666666667,108.87666666666667,82.575,108.87666666666667,78.29333333333334,220.20000000000002 +108.92611111111111,79.55277777777778,108.92611111111111,82.6125,108.92611111111111,78.32888888888888,220.3 +108.97555555555556,79.58888888888887,108.97555555555556,82.64999999999999,108.97555555555556,78.36444444444444,220.4 +109.02499999999999,79.62499999999999,109.02499999999999,82.6875,109.02499999999999,78.4,220.5 +109.07444444444444,79.6611111111111,109.07444444444444,82.725,109.07444444444444,78.43555555555555,220.60000000000002 +109.12388888888889,79.69722222222221,109.12388888888889,82.7625,109.12388888888889,78.47111111111111,220.70000000000002 +109.17333333333333,79.73333333333332,109.17333333333333,82.8,109.17333333333333,78.50666666666666,220.8 +109.22277777777778,79.76944444444443,109.22277777777778,82.83749999999999,109.22277777777778,78.54222222222222,220.9 +109.27222222222223,79.80555555555554,109.27222222222223,82.875,109.27222222222223,78.57777777777778,221.0 +109.32166666666666,79.84166666666665,109.32166666666666,82.9125,109.32166666666666,78.61333333333333,221.10000000000002 +109.3711111111111,79.87777777777777,109.3711111111111,82.95,109.3711111111111,78.64888888888889,221.20000000000002 +109.42055555555555,79.91388888888888,109.42055555555555,82.9875,109.42055555555555,78.68444444444444,221.3 +109.47,79.94999999999999,109.47,83.02499999999999,109.47,78.72,221.4 +109.51944444444445,79.9861111111111,109.51944444444445,83.0625,109.51944444444445,78.75555555555556,221.5 +109.56888888888889,80.02222222222221,109.56888888888889,83.1,109.56888888888889,78.7911111111111,221.60000000000002 +109.61833333333333,80.05833333333332,109.61833333333333,83.1375,109.61833333333333,78.82666666666667,221.70000000000002 +109.66777777777777,80.09444444444443,109.66777777777777,83.175,109.66777777777777,78.86222222222223,221.8 +109.71722222222222,80.13055555555555,109.71722222222222,83.21249999999999,109.71722222222222,78.89777777777778,221.9 +109.76666666666667,80.16666666666666,109.76666666666667,83.25,109.76666666666667,78.93333333333334,222.0 +109.81611111111111,80.20277777777777,109.81611111111111,83.2875,109.81611111111111,78.96888888888888,222.10000000000002 +109.86555555555556,80.23888888888888,109.86555555555556,83.325,109.86555555555556,79.00444444444445,222.20000000000002 +109.91499999999999,80.27499999999999,109.91499999999999,83.3625,109.91499999999999,79.04,222.3 +109.96444444444444,80.3111111111111,109.96444444444444,83.39999999999999,109.96444444444444,79.07555555555555,222.4 +110.01388888888889,80.34722222222221,110.01388888888889,83.4375,110.01388888888889,79.11111111111111,222.5 +110.06333333333333,80.38333333333333,110.06333333333333,83.475,110.06333333333333,79.14666666666666,222.60000000000002 +110.11277777777778,80.41944444444444,110.11277777777778,83.5125,110.11277777777778,79.18222222222222,222.70000000000002 +110.16222222222223,80.45555555555555,110.16222222222223,83.55,110.16222222222223,79.21777777777778,222.8 +110.21166666666666,80.49166666666666,110.21166666666666,83.58749999999999,110.21166666666666,79.25333333333333,222.9 +110.2611111111111,80.52777777777777,110.2611111111111,83.625,110.2611111111111,79.28888888888889,223.0 +110.31055555555555,80.56388888888888,110.31055555555555,83.6625,110.31055555555555,79.32444444444444,223.10000000000002 +110.36,80.6,110.36,83.7,110.36,79.36,223.20000000000002 +110.40944444444445,80.6361111111111,110.40944444444445,83.7375,110.40944444444445,79.39555555555556,223.3 +110.4588888888889,80.67222222222222,110.4588888888889,83.77499999999999,110.4588888888889,79.43111111111111,223.4 +110.50833333333333,80.70833333333333,110.50833333333333,83.8125,110.50833333333333,79.46666666666667,223.5 +110.55777777777777,80.74444444444444,110.55777777777777,83.85,110.55777777777777,79.50222222222222,223.60000000000002 +110.60722222222222,80.78055555555555,110.60722222222222,83.8875,110.60722222222222,79.53777777777778,223.70000000000002 +110.65666666666667,80.81666666666666,110.65666666666667,83.925,110.65666666666667,79.57333333333334,223.8 +110.70611111111111,80.85277777777777,110.70611111111111,83.96249999999999,110.70611111111111,79.60888888888888,223.9 +110.75555555555556,80.88888888888889,110.75555555555556,84.0,110.75555555555556,79.64444444444445,224.0 +110.80499999999999,80.925,110.80499999999999,84.0375,110.80499999999999,79.68,224.10000000000002 +110.85444444444444,80.96111111111111,110.85444444444444,84.075,110.85444444444444,79.71555555555555,224.20000000000002 +110.90388888888889,80.99722222222222,110.90388888888889,84.1125,110.90388888888889,79.75111111111111,224.3 +110.95333333333333,81.03333333333333,110.95333333333333,84.14999999999999,110.95333333333333,79.78666666666666,224.4 +111.00277777777778,81.06944444444444,111.00277777777778,84.1875,111.00277777777778,79.82222222222222,224.5 +111.05222222222223,81.10555555555555,111.05222222222223,84.225,111.05222222222223,79.85777777777778,224.60000000000002 +111.10166666666666,81.14166666666667,111.10166666666666,84.2625,111.10166666666666,79.89333333333333,224.70000000000002 +111.1511111111111,81.17777777777778,111.1511111111111,84.3,111.1511111111111,79.92888888888889,224.8 +111.20055555555555,81.21388888888887,111.20055555555555,84.33749999999999,111.20055555555555,79.96444444444444,224.9 +111.25,81.24999999999999,111.25,84.375,111.25,80.0,225.0 +111.29944444444445,81.2861111111111,111.29944444444445,84.4125,111.29944444444445,80.03555555555556,225.10000000000002 +111.3488888888889,81.32222222222221,111.3488888888889,84.45,111.3488888888889,80.07111111111111,225.20000000000002 +111.39833333333333,81.35833333333332,111.39833333333333,84.4875,111.39833333333333,80.10666666666667,225.3 +111.44777777777777,81.39444444444443,111.44777777777777,84.52499999999999,111.44777777777777,80.14222222222222,225.4 +111.49722222222222,81.43055555555554,111.49722222222222,84.5625,111.49722222222222,80.17777777777778,225.5 +111.54666666666667,81.46666666666665,111.54666666666667,84.6,111.54666666666667,80.21333333333334,225.60000000000002 +111.59611111111111,81.50277777777777,111.59611111111111,84.6375,111.59611111111111,80.24888888888889,225.70000000000002 +111.64555555555556,81.53888888888888,111.64555555555556,84.675,111.64555555555556,80.28444444444445,225.8 +111.695,81.57499999999999,111.695,84.71249999999999,111.695,80.32,225.9 +111.74444444444444,81.6111111111111,111.74444444444444,84.75,111.74444444444444,80.35555555555555,226.0 +111.79388888888889,81.64722222222221,111.79388888888889,84.7875,111.79388888888889,80.39111111111112,226.10000000000002 +111.84333333333333,81.68333333333332,111.84333333333333,84.825,111.84333333333333,80.42666666666666,226.20000000000002 +111.89277777777778,81.71944444444443,111.89277777777778,84.8625,111.89277777777778,80.46222222222222,226.3 +111.94222222222223,81.75555555555555,111.94222222222223,84.89999999999999,111.94222222222223,80.49777777777778,226.4 +111.99166666666666,81.79166666666666,111.99166666666666,84.9375,111.99166666666666,80.53333333333333,226.5 +112.0411111111111,81.82777777777777,112.0411111111111,84.975,112.0411111111111,80.56888888888889,226.60000000000002 +112.09055555555555,81.86388888888888,112.09055555555555,85.0125,112.09055555555555,80.60444444444444,226.70000000000002 +112.14,81.89999999999999,112.14,85.05,112.14,80.64,226.8 +112.18944444444445,81.9361111111111,112.18944444444445,85.08749999999999,112.18944444444445,80.67555555555556,226.9 +112.23888888888888,81.97222222222221,112.23888888888888,85.125,112.23888888888888,80.71111111111111,227.0 +112.28833333333333,82.00833333333333,112.28833333333333,85.1625,112.28833333333333,80.74666666666667,227.10000000000002 +112.33777777777777,82.04444444444444,112.33777777777777,85.2,112.33777777777777,80.78222222222222,227.20000000000002 +112.38722222222222,82.08055555555555,112.38722222222222,85.2375,112.38722222222222,80.81777777777778,227.3 +112.43666666666667,82.11666666666666,112.43666666666667,85.27499999999999,112.43666666666667,80.85333333333334,227.4 +112.48611111111111,82.15277777777777,112.48611111111111,85.3125,112.48611111111111,80.88888888888889,227.5 +112.53555555555555,82.18888888888888,112.53555555555555,85.35,112.53555555555555,80.92444444444445,227.60000000000002 +112.585,82.225,112.585,85.3875,112.585,80.96,227.70000000000002 +112.63444444444444,82.2611111111111,112.63444444444444,85.425,112.63444444444444,80.99555555555555,227.8 +112.68388888888889,82.29722222222222,112.68388888888889,85.46249999999999,112.68388888888889,81.03111111111112,227.9 +112.73333333333333,82.33333333333333,112.73333333333333,85.5,112.73333333333333,81.06666666666666,228.0 +112.78277777777778,82.36944444444444,112.78277777777778,85.5375,112.78277777777778,81.10222222222222,228.10000000000002 +112.83222222222221,82.40555555555555,112.83222222222221,85.575,112.83222222222221,81.13777777777777,228.20000000000002 +112.88166666666666,82.44166666666666,112.88166666666666,85.6125,112.88166666666666,81.17333333333333,228.3 +112.93111111111111,82.47777777777777,112.93111111111111,85.64999999999999,112.93111111111111,81.2088888888889,228.4 +112.98055555555555,82.51388888888889,112.98055555555555,85.6875,112.98055555555555,81.24444444444444,228.5 +113.03,82.55,113.03,85.725,113.03,81.28,228.60000000000002 +113.07944444444445,82.58611111111111,113.07944444444445,85.7625,113.07944444444445,81.31555555555556,228.70000000000002 +113.12888888888888,82.62222222222222,113.12888888888888,85.8,113.12888888888888,81.35111111111111,228.8 +113.17833333333333,82.65833333333333,113.17833333333333,85.83749999999999,113.17833333333333,81.38666666666667,228.9 +113.22777777777777,82.69444444444444,113.22777777777777,85.875,113.22777777777777,81.42222222222222,229.0 +113.27722222222222,82.73055555555555,113.27722222222222,85.9125,113.27722222222222,81.45777777777778,229.10000000000002 +113.32666666666667,82.76666666666667,113.32666666666667,85.95,113.32666666666667,81.49333333333334,229.20000000000002 +113.37611111111111,82.80277777777776,113.37611111111111,85.9875,113.37611111111111,81.52888888888889,229.3 +113.42555555555555,82.83888888888887,113.42555555555555,86.02499999999999,113.42555555555555,81.56444444444445,229.4 +113.475,82.87499999999999,113.475,86.0625,113.475,81.6,229.5 +113.52444444444444,82.9111111111111,113.52444444444444,86.1,113.52444444444444,81.63555555555556,229.60000000000002 +113.57388888888889,82.94722222222221,113.57388888888889,86.1375,113.57388888888889,81.67111111111112,229.70000000000002 +113.62333333333333,82.98333333333332,113.62333333333333,86.175,113.62333333333333,81.70666666666666,229.8 +113.67277777777778,83.01944444444443,113.67277777777778,86.21249999999999,113.67277777777778,81.74222222222222,229.9 +113.72222222222221,83.05555555555554,113.72222222222221,86.25,113.72222222222221,81.77777777777777,230.0 +113.77166666666666,83.09166666666665,113.77166666666666,86.2875,113.77166666666666,81.81333333333333,230.10000000000002 +113.82111111111111,83.12777777777777,113.82111111111111,86.325,113.82111111111111,81.8488888888889,230.20000000000002 +113.87055555555555,83.16388888888888,113.87055555555555,86.3625,113.87055555555555,81.88444444444444,230.3 +113.92,83.19999999999999,113.92,86.39999999999999,113.92,81.92,230.4 +113.96944444444445,83.2361111111111,113.96944444444445,86.4375,113.96944444444445,81.95555555555555,230.5 +114.01888888888888,83.27222222222221,114.01888888888888,86.475,114.01888888888888,81.99111111111111,230.60000000000002 +114.06833333333333,83.30833333333332,114.06833333333333,86.5125,114.06833333333333,82.02666666666667,230.70000000000002 +114.11777777777777,83.34444444444443,114.11777777777777,86.55,114.11777777777777,82.06222222222222,230.8 +114.16722222222222,83.38055555555555,114.16722222222222,86.58749999999999,114.16722222222222,82.09777777777778,230.9 +114.21666666666667,83.41666666666666,114.21666666666667,86.625,114.21666666666667,82.13333333333334,231.0 +114.26611111111112,83.45277777777777,114.26611111111112,86.6625,114.26611111111112,82.16888888888889,231.10000000000002 +114.31555555555555,83.48888888888888,114.31555555555555,86.7,114.31555555555555,82.20444444444445,231.20000000000002 +114.365,83.52499999999999,114.365,86.7375,114.365,82.24,231.3 +114.41444444444444,83.5611111111111,114.41444444444444,86.77499999999999,114.41444444444444,82.27555555555556,231.4 +114.46388888888889,83.59722222222221,114.46388888888889,86.8125,114.46388888888889,82.31111111111112,231.5 +114.51333333333334,83.63333333333333,114.51333333333334,86.85,114.51333333333334,82.34666666666666,231.60000000000002 +114.56277777777778,83.66944444444444,114.56277777777778,86.8875,114.56277777777778,82.38222222222223,231.70000000000002 +114.61222222222221,83.70555555555555,114.61222222222221,86.925,114.61222222222221,82.41777777777777,231.8 +114.66166666666666,83.74166666666666,114.66166666666666,86.96249999999999,114.66166666666666,82.45333333333333,231.9 +114.71111111111111,83.77777777777777,114.71111111111111,87.0,114.71111111111111,82.4888888888889,232.0 +114.76055555555556,83.81388888888888,114.76055555555556,87.0375,114.76055555555556,82.52444444444444,232.10000000000002 +114.81,83.85,114.81,87.075,114.81,82.56,232.20000000000002 +114.85944444444445,83.8861111111111,114.85944444444445,87.1125,114.85944444444445,82.59555555555555,232.3 +114.90888888888888,83.92222222222222,114.90888888888888,87.14999999999999,114.90888888888888,82.63111111111111,232.4 +114.95833333333333,83.95833333333333,114.95833333333333,87.1875,114.95833333333333,82.66666666666667,232.5 +115.00777777777778,83.99444444444444,115.00777777777778,87.225,115.00777777777778,82.70222222222222,232.60000000000002 +115.05722222222222,84.03055555555555,115.05722222222222,87.2625,115.05722222222222,82.73777777777778,232.70000000000002 +115.10666666666667,84.06666666666666,115.10666666666667,87.3,115.10666666666667,82.77333333333333,232.8 +115.15611111111112,84.10277777777777,115.15611111111112,87.33749999999999,115.15611111111112,82.80888888888889,232.9 +115.20555555555555,84.13888888888889,115.20555555555555,87.375,115.20555555555555,82.84444444444445,233.0 +115.255,84.175,115.255,87.4125,115.255,82.88,233.10000000000002 +115.30444444444444,84.21111111111111,115.30444444444444,87.45,115.30444444444444,82.91555555555556,233.20000000000002 +115.35388888888889,84.24722222222222,115.35388888888889,87.4875,115.35388888888889,82.95111111111112,233.3 +115.40333333333334,84.28333333333333,115.40333333333334,87.52499999999999,115.40333333333334,82.98666666666666,233.4 +115.45277777777778,84.31944444444444,115.45277777777778,87.5625,115.45277777777778,83.02222222222223,233.5 +115.50222222222222,84.35555555555555,115.50222222222222,87.6,115.50222222222222,83.05777777777777,233.60000000000002 +115.55166666666666,84.39166666666667,115.55166666666666,87.6375,115.55166666666666,83.09333333333333,233.70000000000002 +115.60111111111111,84.42777777777776,115.60111111111111,87.675,115.60111111111111,83.1288888888889,233.8 +115.65055555555556,84.46388888888887,115.65055555555556,87.71249999999999,115.65055555555556,83.16444444444444,233.9 +115.7,84.49999999999999,115.7,87.75,115.7,83.2,234.0 +115.74944444444444,84.5361111111111,115.74944444444444,87.7875,115.74944444444444,83.23555555555555,234.10000000000002 +115.79888888888888,84.57222222222221,115.79888888888888,87.825,115.79888888888888,83.27111111111111,234.20000000000002 +115.84833333333333,84.60833333333332,115.84833333333333,87.8625,115.84833333333333,83.30666666666667,234.3 +115.89777777777778,84.64444444444443,115.89777777777778,87.89999999999999,115.89777777777778,83.34222222222222,234.4 +115.94722222222222,84.68055555555554,115.94722222222222,87.9375,115.94722222222222,83.37777777777778,234.5 +115.99666666666667,84.71666666666665,115.99666666666667,87.975,115.99666666666667,83.41333333333333,234.60000000000002 +116.0461111111111,84.75277777777777,116.0461111111111,88.0125,116.0461111111111,83.44888888888889,234.70000000000002 +116.09555555555555,84.78888888888888,116.09555555555555,88.05,116.09555555555555,83.48444444444445,234.8 +116.145,84.82499999999999,116.145,88.08749999999999,116.145,83.52,234.9 +116.19444444444444,84.8611111111111,116.19444444444444,88.125,116.19444444444444,83.55555555555556,235.0 +116.24388888888889,84.89722222222221,116.24388888888889,88.1625,116.24388888888889,83.5911111111111,235.10000000000002 +116.29333333333334,84.93333333333332,116.29333333333334,88.2,116.29333333333334,83.62666666666667,235.20000000000002 +116.34277777777777,84.96944444444443,116.34277777777777,88.2375,116.34277777777777,83.66222222222223,235.3 +116.39222222222222,85.00555555555555,116.39222222222222,88.27499999999999,116.39222222222222,83.69777777777777,235.4 +116.44166666666666,85.04166666666666,116.44166666666666,88.3125,116.44166666666666,83.73333333333333,235.5 +116.49111111111111,85.07777777777777,116.49111111111111,88.35,116.49111111111111,83.7688888888889,235.60000000000002 +116.54055555555556,85.11388888888888,116.54055555555556,88.3875,116.54055555555556,83.80444444444444,235.70000000000002 +116.59,85.14999999999999,116.59,88.425,116.59,83.84,235.8 +116.63944444444444,85.1861111111111,116.63944444444444,88.46249999999999,116.63944444444444,83.87555555555555,235.9 +116.68888888888888,85.22222222222221,116.68888888888888,88.5,116.68888888888888,83.91111111111111,236.0 +116.73833333333333,85.25833333333333,116.73833333333333,88.5375,116.73833333333333,83.94666666666667,236.10000000000002 +116.78777777777778,85.29444444444444,116.78777777777778,88.575,116.78777777777778,83.98222222222222,236.20000000000002 +116.83722222222222,85.33055555555555,116.83722222222222,88.6125,116.83722222222222,84.01777777777778,236.3 +116.88666666666667,85.36666666666666,116.88666666666667,88.64999999999999,116.88666666666667,84.05333333333333,236.4 +116.9361111111111,85.40277777777777,116.9361111111111,88.6875,116.9361111111111,84.08888888888889,236.5 +116.98555555555555,85.43888888888888,116.98555555555555,88.725,116.98555555555555,84.12444444444445,236.60000000000002 +117.035,85.475,117.035,88.7625,117.035,84.16,236.70000000000002 +117.08444444444444,85.5111111111111,117.08444444444444,88.8,117.08444444444444,84.19555555555556,236.8 +117.13388888888889,85.54722222222222,117.13388888888889,88.83749999999999,117.13388888888889,84.2311111111111,236.9 +117.18333333333334,85.58333333333333,117.18333333333334,88.875,117.18333333333334,84.26666666666667,237.0 +117.23277777777777,85.61944444444444,117.23277777777777,88.9125,117.23277777777777,84.30222222222223,237.10000000000002 +117.28222222222222,85.65555555555555,117.28222222222222,88.95,117.28222222222222,84.33777777777777,237.20000000000002 +117.33166666666666,85.69166666666666,117.33166666666666,88.9875,117.33166666666666,84.37333333333333,237.3 +117.38111111111111,85.72777777777777,117.38111111111111,89.02499999999999,117.38111111111111,84.40888888888888,237.4 +117.43055555555556,85.76388888888889,117.43055555555556,89.0625,117.43055555555556,84.44444444444444,237.5 +117.48,85.8,117.48,89.1,117.48,84.48,237.60000000000002 +117.52944444444444,85.83611111111111,117.52944444444444,89.1375,117.52944444444444,84.51555555555555,237.70000000000002 +117.57888888888888,85.87222222222222,117.57888888888888,89.175,117.57888888888888,84.55111111111111,237.8 +117.62833333333333,85.90833333333333,117.62833333333333,89.21249999999999,117.62833333333333,84.58666666666667,237.9 +117.67777777777778,85.94444444444444,117.67777777777778,89.25,117.67777777777778,84.62222222222222,238.0 +117.72722222222222,85.98055555555555,117.72722222222222,89.2875,117.72722222222222,84.65777777777778,238.10000000000002 +117.77666666666667,86.01666666666665,117.77666666666667,89.325,117.77666666666667,84.69333333333333,238.20000000000002 +117.8261111111111,86.05277777777776,117.8261111111111,89.3625,117.8261111111111,84.72888888888889,238.3 +117.87555555555555,86.08888888888887,117.87555555555555,89.39999999999999,117.87555555555555,84.76444444444445,238.4 +117.925,86.12499999999999,117.925,89.4375,117.925,84.8,238.5 +117.97444444444444,86.1611111111111,117.97444444444444,89.475,117.97444444444444,84.83555555555556,238.60000000000002 +118.02388888888889,86.19722222222221,118.02388888888889,89.5125,118.02388888888889,84.8711111111111,238.70000000000002 +118.07333333333334,86.23333333333332,118.07333333333334,89.55,118.07333333333334,84.90666666666667,238.8 +118.12277777777777,86.26944444444443,118.12277777777777,89.58749999999999,118.12277777777777,84.94222222222223,238.9 +118.17222222222222,86.30555555555554,118.17222222222222,89.625,118.17222222222222,84.97777777777777,239.0 +118.22166666666666,86.34166666666665,118.22166666666666,89.6625,118.22166666666666,85.01333333333334,239.10000000000002 +118.27111111111111,86.37777777777777,118.27111111111111,89.7,118.27111111111111,85.04888888888888,239.20000000000002 +118.32055555555556,86.41388888888888,118.32055555555556,89.7375,118.32055555555556,85.08444444444444,239.3 +118.37,86.44999999999999,118.37,89.77499999999999,118.37,85.12,239.4 +118.41944444444444,86.4861111111111,118.41944444444444,89.8125,118.41944444444444,85.15555555555555,239.5 +118.46888888888888,86.52222222222221,118.46888888888888,89.85,118.46888888888888,85.19111111111111,239.60000000000002 +118.51833333333333,86.55833333333332,118.51833333333333,89.8875,118.51833333333333,85.22666666666667,239.70000000000002 +118.56777777777778,86.59444444444443,118.56777777777778,89.925,118.56777777777778,85.26222222222222,239.8 +118.61722222222222,86.63055555555555,118.61722222222222,89.96249999999999,118.61722222222222,85.29777777777778,239.9 +118.66666666666667,86.66666666666666,118.66666666666667,90.0,118.66666666666667,85.33333333333333,240.0 +118.7161111111111,86.70277777777777,118.7161111111111,90.0375,118.7161111111111,85.36888888888889,240.10000000000002 +118.76555555555555,86.73888888888888,118.76555555555555,90.075,118.76555555555555,85.40444444444445,240.20000000000002 +118.815,86.77499999999999,118.815,90.1125,118.815,85.44,240.3 +118.86444444444444,86.8111111111111,118.86444444444444,90.14999999999999,118.86444444444444,85.47555555555556,240.4 +118.91388888888889,86.84722222222221,118.91388888888889,90.1875,118.91388888888889,85.5111111111111,240.5 +118.96333333333334,86.88333333333333,118.96333333333334,90.225,118.96333333333334,85.54666666666667,240.60000000000002 +119.01277777777777,86.91944444444444,119.01277777777777,90.2625,119.01277777777777,85.58222222222223,240.70000000000002 +119.06222222222222,86.95555555555555,119.06222222222222,90.3,119.06222222222222,85.61777777777777,240.8 +119.11166666666666,86.99166666666666,119.11166666666666,90.33749999999999,119.11166666666666,85.65333333333334,240.9 +119.16111111111111,87.02777777777777,119.16111111111111,90.375,119.16111111111111,85.68888888888888,241.0 +119.21055555555556,87.06388888888888,119.21055555555556,90.4125,119.21055555555556,85.72444444444444,241.10000000000002 +119.26,87.1,119.26,90.45,119.26,85.76,241.20000000000002 +119.30944444444444,87.1361111111111,119.30944444444444,90.4875,119.30944444444444,85.79555555555555,241.3 +119.35888888888888,87.17222222222222,119.35888888888888,90.52499999999999,119.35888888888888,85.83111111111111,241.4 +119.40833333333333,87.20833333333333,119.40833333333333,90.5625,119.40833333333333,85.86666666666666,241.5 +119.45777777777778,87.24444444444444,119.45777777777778,90.6,119.45777777777778,85.90222222222222,241.60000000000002 +119.50722222222223,87.28055555555555,119.50722222222223,90.6375,119.50722222222223,85.93777777777778,241.70000000000002 +119.55666666666666,87.31666666666666,119.55666666666666,90.675,119.55666666666666,85.97333333333333,241.8 +119.6061111111111,87.35277777777777,119.6061111111111,90.71249999999999,119.6061111111111,86.00888888888889,241.9 +119.65555555555555,87.38888888888889,119.65555555555555,90.75,119.65555555555555,86.04444444444445,242.0 +119.705,87.425,119.705,90.7875,119.705,86.08,242.10000000000002 +119.75444444444445,87.46111111111111,119.75444444444445,90.825,119.75444444444445,86.11555555555556,242.20000000000002 +119.80388888888889,87.49722222222222,119.80388888888889,90.8625,119.80388888888889,86.1511111111111,242.3 +119.85333333333332,87.53333333333333,119.85333333333332,90.89999999999999,119.85333333333332,86.18666666666667,242.4 +119.90277777777777,87.56944444444444,119.90277777777777,90.9375,119.90277777777777,86.22222222222223,242.5 +119.95222222222222,87.60555555555555,119.95222222222222,90.975,119.95222222222222,86.25777777777778,242.60000000000002 +120.00166666666667,87.64166666666665,120.00166666666667,91.0125,120.00166666666667,86.29333333333334,242.70000000000002 +120.05111111111111,87.67777777777776,120.05111111111111,91.05,120.05111111111111,86.32888888888888,242.8 +120.10055555555556,87.71388888888887,120.10055555555556,91.08749999999999,120.10055555555556,86.36444444444444,242.9 +120.14999999999999,87.74999999999999,120.14999999999999,91.125,120.14999999999999,86.4,243.0 +120.19944444444444,87.7861111111111,120.19944444444444,91.1625,120.19944444444444,86.43555555555555,243.10000000000002 +120.24888888888889,87.82222222222221,120.24888888888889,91.2,120.24888888888889,86.47111111111111,243.20000000000002 +120.29833333333333,87.85833333333332,120.29833333333333,91.2375,120.29833333333333,86.50666666666666,243.3 +120.34777777777778,87.89444444444443,120.34777777777778,91.27499999999999,120.34777777777778,86.54222222222222,243.4 +120.39722222222223,87.93055555555554,120.39722222222223,91.3125,120.39722222222223,86.57777777777778,243.5 +120.44666666666666,87.96666666666665,120.44666666666666,91.35,120.44666666666666,86.61333333333333,243.60000000000002 +120.4961111111111,88.00277777777777,120.4961111111111,91.3875,120.4961111111111,86.64888888888889,243.70000000000002 +120.54555555555555,88.03888888888888,120.54555555555555,91.425,120.54555555555555,86.68444444444444,243.8 +120.595,88.07499999999999,120.595,91.46249999999999,120.595,86.72,243.9 +120.64444444444445,88.1111111111111,120.64444444444445,91.5,120.64444444444445,86.75555555555556,244.0 +120.69388888888889,88.14722222222221,120.69388888888889,91.5375,120.69388888888889,86.7911111111111,244.10000000000002 +120.74333333333333,88.18333333333332,120.74333333333333,91.575,120.74333333333333,86.82666666666667,244.20000000000002 +120.79277777777777,88.21944444444443,120.79277777777777,91.6125,120.79277777777777,86.86222222222223,244.3 +120.84222222222222,88.25555555555555,120.84222222222222,91.64999999999999,120.84222222222222,86.89777777777778,244.4 +120.89166666666667,88.29166666666666,120.89166666666667,91.6875,120.89166666666667,86.93333333333334,244.5 +120.94111111111111,88.32777777777777,120.94111111111111,91.725,120.94111111111111,86.96888888888888,244.60000000000002 +120.99055555555556,88.36388888888888,120.99055555555556,91.7625,120.99055555555556,87.00444444444445,244.70000000000002 +121.03999999999999,88.39999999999999,121.03999999999999,91.8,121.03999999999999,87.04,244.8 +121.08944444444444,88.4361111111111,121.08944444444444,91.83749999999999,121.08944444444444,87.07555555555555,244.9 +121.13888888888889,88.47222222222221,121.13888888888889,91.875,121.13888888888889,87.11111111111111,245.0 +121.18833333333333,88.50833333333333,121.18833333333333,91.9125,121.18833333333333,87.14666666666666,245.10000000000002 +121.23777777777778,88.54444444444444,121.23777777777778,91.95,121.23777777777778,87.18222222222222,245.20000000000002 +121.28722222222223,88.58055555555555,121.28722222222223,91.9875,121.28722222222223,87.21777777777778,245.3 +121.33666666666666,88.61666666666666,121.33666666666666,92.02499999999999,121.33666666666666,87.25333333333333,245.4 +121.3861111111111,88.65277777777777,121.3861111111111,92.0625,121.3861111111111,87.28888888888889,245.5 +121.43555555555555,88.68888888888888,121.43555555555555,92.1,121.43555555555555,87.32444444444444,245.60000000000002 +121.485,88.725,121.485,92.1375,121.485,87.36,245.70000000000002 +121.53444444444445,88.7611111111111,121.53444444444445,92.175,121.53444444444445,87.39555555555556,245.8 +121.5838888888889,88.79722222222222,121.5838888888889,92.21249999999999,121.5838888888889,87.43111111111111,245.9 +121.63333333333333,88.83333333333333,121.63333333333333,92.25,121.63333333333333,87.46666666666667,246.0 +121.68277777777777,88.86944444444444,121.68277777777777,92.2875,121.68277777777777,87.50222222222222,246.10000000000002 +121.73222222222222,88.90555555555555,121.73222222222222,92.325,121.73222222222222,87.53777777777778,246.20000000000002 +121.78166666666667,88.94166666666666,121.78166666666667,92.3625,121.78166666666667,87.57333333333334,246.3 +121.83111111111111,88.97777777777777,121.83111111111111,92.39999999999999,121.83111111111111,87.60888888888888,246.4 +121.88055555555556,89.01388888888889,121.88055555555556,92.4375,121.88055555555556,87.64444444444445,246.5 +121.92999999999999,89.05,121.92999999999999,92.475,121.92999999999999,87.68,246.60000000000002 +121.97944444444444,89.08611111111111,121.97944444444444,92.5125,121.97944444444444,87.71555555555555,246.70000000000002 +122.02888888888889,89.12222222222222,122.02888888888889,92.55,122.02888888888889,87.75111111111111,246.8 +122.07833333333333,89.15833333333333,122.07833333333333,92.58749999999999,122.07833333333333,87.78666666666666,246.9 +122.12777777777778,89.19444444444444,122.12777777777778,92.625,122.12777777777778,87.82222222222222,247.0 +122.17722222222223,89.23055555555554,122.17722222222223,92.6625,122.17722222222223,87.85777777777778,247.10000000000002 +122.22666666666666,89.26666666666665,122.22666666666666,92.7,122.22666666666666,87.89333333333333,247.20000000000002 +122.2761111111111,89.30277777777776,122.2761111111111,92.7375,122.2761111111111,87.92888888888889,247.3 +122.32555555555555,89.33888888888887,122.32555555555555,92.77499999999999,122.32555555555555,87.96444444444444,247.4 +122.375,89.37499999999999,122.375,92.8125,122.375,88.0,247.5 +122.42444444444445,89.4111111111111,122.42444444444445,92.85,122.42444444444445,88.03555555555556,247.60000000000002 +122.4738888888889,89.44722222222221,122.4738888888889,92.8875,122.4738888888889,88.07111111111111,247.70000000000002 +122.52333333333333,89.48333333333332,122.52333333333333,92.925,122.52333333333333,88.10666666666667,247.8 +122.57277777777777,89.51944444444443,122.57277777777777,92.96249999999999,122.57277777777777,88.14222222222222,247.9 +122.62222222222222,89.55555555555554,122.62222222222222,93.0,122.62222222222222,88.17777777777778,248.0 +122.67166666666667,89.59166666666665,122.67166666666667,93.0375,122.67166666666667,88.21333333333334,248.10000000000002 +122.72111111111111,89.62777777777777,122.72111111111111,93.075,122.72111111111111,88.24888888888889,248.20000000000002 +122.77055555555556,89.66388888888888,122.77055555555556,93.1125,122.77055555555556,88.28444444444445,248.3 +122.82,89.69999999999999,122.82,93.14999999999999,122.82,88.32,248.4 +122.86944444444444,89.7361111111111,122.86944444444444,93.1875,122.86944444444444,88.35555555555555,248.5 +122.91888888888889,89.77222222222221,122.91888888888889,93.225,122.91888888888889,88.39111111111112,248.60000000000002 +122.96833333333333,89.80833333333332,122.96833333333333,93.2625,122.96833333333333,88.42666666666666,248.70000000000002 +123.01777777777778,89.84444444444443,123.01777777777778,93.3,123.01777777777778,88.46222222222222,248.8 +123.06722222222221,89.88055555555555,123.06722222222221,93.33749999999999,123.06722222222221,88.49777777777778,248.9 +123.11666666666666,89.91666666666666,123.11666666666666,93.375,123.11666666666666,88.53333333333333,249.0 +123.1661111111111,89.95277777777777,123.1661111111111,93.4125,123.1661111111111,88.56888888888889,249.10000000000002 +123.21555555555555,89.98888888888888,123.21555555555555,93.45,123.21555555555555,88.60444444444444,249.20000000000002 +123.265,90.02499999999999,123.265,93.4875,123.265,88.64,249.3 +123.31444444444445,90.0611111111111,123.31444444444445,93.52499999999999,123.31444444444445,88.67555555555556,249.4 +123.36388888888888,90.09722222222221,123.36388888888888,93.5625,123.36388888888888,88.71111111111111,249.5 +123.41333333333333,90.13333333333333,123.41333333333333,93.6,123.41333333333333,88.74666666666667,249.60000000000002 +123.46277777777777,90.16944444444444,123.46277777777777,93.6375,123.46277777777777,88.78222222222222,249.70000000000002 +123.51222222222222,90.20555555555555,123.51222222222222,93.675,123.51222222222222,88.81777777777778,249.8 +123.56166666666667,90.24166666666666,123.56166666666667,93.71249999999999,123.56166666666667,88.85333333333334,249.9 +123.61111111111111,90.27777777777777,123.61111111111111,93.75,123.61111111111111,88.88888888888889,250.0 +123.66055555555555,90.31388888888888,123.66055555555555,93.7875,123.66055555555555,88.92444444444445,250.10000000000002 +123.71,90.35,123.71,93.825,123.71,88.96,250.20000000000002 +123.75944444444444,90.3861111111111,123.75944444444444,93.8625,123.75944444444444,88.99555555555555,250.3 +123.80888888888889,90.42222222222222,123.80888888888889,93.89999999999999,123.80888888888889,89.03111111111112,250.4 +123.85833333333333,90.45833333333333,123.85833333333333,93.9375,123.85833333333333,89.06666666666666,250.5 +123.90777777777778,90.49444444444444,123.90777777777778,93.975,123.90777777777778,89.10222222222222,250.60000000000002 +123.95722222222221,90.53055555555555,123.95722222222221,94.0125,123.95722222222221,89.13777777777777,250.70000000000002 +124.00666666666666,90.56666666666666,124.00666666666666,94.05,124.00666666666666,89.17333333333333,250.8 +124.05611111111111,90.60277777777777,124.05611111111111,94.08749999999999,124.05611111111111,89.2088888888889,250.9 +124.10555555555555,90.63888888888889,124.10555555555555,94.125,124.10555555555555,89.24444444444444,251.0 +124.155,90.675,124.155,94.1625,124.155,89.28,251.10000000000002 +124.20444444444445,90.71111111111111,124.20444444444445,94.2,124.20444444444445,89.31555555555556,251.20000000000002 +124.25388888888888,90.74722222222222,124.25388888888888,94.2375,124.25388888888888,89.35111111111111,251.3 +124.30333333333333,90.78333333333333,124.30333333333333,94.27499999999999,124.30333333333333,89.38666666666667,251.4 +124.35277777777777,90.81944444444444,124.35277777777777,94.3125,124.35277777777777,89.42222222222222,251.5 +124.40222222222222,90.85555555555554,124.40222222222222,94.35,124.40222222222222,89.45777777777778,251.60000000000002 +124.45166666666667,90.89166666666665,124.45166666666667,94.3875,124.45166666666667,89.49333333333334,251.70000000000002 +124.50111111111111,90.92777777777776,124.50111111111111,94.425,124.50111111111111,89.52888888888889,251.8 +124.55055555555555,90.96388888888887,124.55055555555555,94.46249999999999,124.55055555555555,89.56444444444445,251.9 +124.6,90.99999999999999,124.6,94.5,124.6,89.6,252.0 +124.64944444444444,91.0361111111111,124.64944444444444,94.5375,124.64944444444444,89.63555555555556,252.10000000000002 +124.69888888888889,91.07222222222221,124.69888888888889,94.575,124.69888888888889,89.67111111111112,252.20000000000002 +124.74833333333333,91.10833333333332,124.74833333333333,94.6125,124.74833333333333,89.70666666666666,252.3 +124.79777777777778,91.14444444444443,124.79777777777778,94.64999999999999,124.79777777777778,89.74222222222222,252.4 +124.84722222222221,91.18055555555554,124.84722222222221,94.6875,124.84722222222221,89.77777777777777,252.5 +124.89666666666666,91.21666666666665,124.89666666666666,94.725,124.89666666666666,89.81333333333333,252.60000000000002 +124.94611111111111,91.25277777777777,124.94611111111111,94.7625,124.94611111111111,89.8488888888889,252.70000000000002 +124.99555555555555,91.28888888888888,124.99555555555555,94.8,124.99555555555555,89.88444444444444,252.8 +125.045,91.32499999999999,125.045,94.83749999999999,125.045,89.92,252.9 +125.09444444444445,91.3611111111111,125.09444444444445,94.875,125.09444444444445,89.95555555555555,253.0 +125.14388888888888,91.39722222222221,125.14388888888888,94.9125,125.14388888888888,89.99111111111111,253.10000000000002 +125.19333333333333,91.43333333333332,125.19333333333333,94.95,125.19333333333333,90.02666666666667,253.20000000000002 +125.24277777777777,91.46944444444443,125.24277777777777,94.9875,125.24277777777777,90.06222222222222,253.3 +125.29222222222222,91.50555555555555,125.29222222222222,95.02499999999999,125.29222222222222,90.09777777777778,253.4 +125.34166666666667,91.54166666666666,125.34166666666667,95.0625,125.34166666666667,90.13333333333334,253.5 +125.39111111111112,91.57777777777777,125.39111111111112,95.1,125.39111111111112,90.16888888888889,253.60000000000002 +125.44055555555555,91.61388888888888,125.44055555555555,95.1375,125.44055555555555,90.20444444444445,253.70000000000002 +125.49,91.64999999999999,125.49,95.175,125.49,90.24,253.8 +125.53944444444444,91.6861111111111,125.53944444444444,95.21249999999999,125.53944444444444,90.27555555555556,253.9 +125.58888888888889,91.72222222222221,125.58888888888889,95.25,125.58888888888889,90.31111111111112,254.0 +125.63833333333334,91.75833333333333,125.63833333333334,95.2875,125.63833333333334,90.34666666666666,254.10000000000002 +125.68777777777778,91.79444444444444,125.68777777777778,95.325,125.68777777777778,90.38222222222223,254.20000000000002 +125.73722222222221,91.83055555555555,125.73722222222221,95.3625,125.73722222222221,90.41777777777777,254.3 +125.78666666666666,91.86666666666666,125.78666666666666,95.39999999999999,125.78666666666666,90.45333333333333,254.4 +125.83611111111111,91.90277777777777,125.83611111111111,95.4375,125.83611111111111,90.4888888888889,254.5 +125.88555555555556,91.93888888888888,125.88555555555556,95.475,125.88555555555556,90.52444444444444,254.60000000000002 +125.935,91.975,125.935,95.5125,125.935,90.56,254.70000000000002 +125.98444444444445,92.0111111111111,125.98444444444445,95.55,125.98444444444445,90.59555555555555,254.8 +126.03388888888888,92.04722222222222,126.03388888888888,95.58749999999999,126.03388888888888,90.63111111111111,254.9 +126.08333333333333,92.08333333333333,126.08333333333333,95.625,126.08333333333333,90.66666666666667,255.0 +126.13277777777778,92.11944444444444,126.13277777777778,95.6625,126.13277777777778,90.70222222222222,255.10000000000002 +126.18222222222222,92.15555555555555,126.18222222222222,95.7,126.18222222222222,90.73777777777778,255.20000000000002 +126.23166666666667,92.19166666666666,126.23166666666667,95.7375,126.23166666666667,90.77333333333333,255.3 +126.28111111111112,92.22777777777777,126.28111111111112,95.77499999999999,126.28111111111112,90.80888888888889,255.4 +126.33055555555555,92.26388888888889,126.33055555555555,95.8125,126.33055555555555,90.84444444444445,255.5 +126.38,92.3,126.38,95.85,126.38,90.88,255.60000000000002 +126.42944444444444,92.33611111111111,126.42944444444444,95.8875,126.42944444444444,90.91555555555556,255.70000000000002 +126.47888888888889,92.37222222222222,126.47888888888889,95.925,126.47888888888889,90.95111111111112,255.8 +126.52833333333334,92.40833333333333,126.52833333333334,95.96249999999999,126.52833333333334,90.98666666666666,255.9 +126.57777777777778,92.44444444444443,126.57777777777778,96.0,126.57777777777778,91.02222222222223,256.0 +126.62722222222222,92.48055555555554,126.62722222222222,96.0375,126.62722222222222,91.05777777777777,256.1 +126.67666666666666,92.51666666666665,126.67666666666666,96.075,126.67666666666666,91.09333333333333,256.2 +126.72611111111111,92.55277777777776,126.72611111111111,96.1125,126.72611111111111,91.1288888888889,256.3 +126.77555555555556,92.58888888888887,126.77555555555556,96.14999999999999,126.77555555555556,91.16444444444444,256.40000000000003 +126.825,92.62499999999999,126.825,96.1875,126.825,91.2,256.5 +126.87444444444444,92.6611111111111,126.87444444444444,96.225,126.87444444444444,91.23555555555555,256.6 +126.92388888888888,92.69722222222221,126.92388888888888,96.2625,126.92388888888888,91.27111111111111,256.7 +126.97333333333333,92.73333333333332,126.97333333333333,96.3,126.97333333333333,91.30666666666667,256.8 +127.02277777777778,92.76944444444443,127.02277777777778,96.33749999999999,127.02277777777778,91.34222222222222,256.90000000000003 +127.07222222222222,92.80555555555554,127.07222222222222,96.375,127.07222222222222,91.37777777777778,257.0 +127.12166666666667,92.84166666666665,127.12166666666667,96.4125,127.12166666666667,91.41333333333333,257.1 +127.1711111111111,92.87777777777777,127.1711111111111,96.45,127.1711111111111,91.44888888888889,257.2 +127.22055555555555,92.91388888888888,127.22055555555555,96.4875,127.22055555555555,91.48444444444445,257.3 +127.27,92.94999999999999,127.27,96.52499999999999,127.27,91.52,257.40000000000003 +127.31944444444444,92.9861111111111,127.31944444444444,96.5625,127.31944444444444,91.55555555555556,257.5 +127.36888888888889,93.02222222222221,127.36888888888889,96.6,127.36888888888889,91.5911111111111,257.6 +127.41833333333334,93.05833333333332,127.41833333333334,96.6375,127.41833333333334,91.62666666666667,257.7 +127.46777777777777,93.09444444444443,127.46777777777777,96.675,127.46777777777777,91.66222222222223,257.8 +127.51722222222222,93.13055555555555,127.51722222222222,96.71249999999999,127.51722222222222,91.69777777777777,257.90000000000003 +127.56666666666666,93.16666666666666,127.56666666666666,96.75,127.56666666666666,91.73333333333333,258.0 +127.61611111111111,93.20277777777777,127.61611111111111,96.7875,127.61611111111111,91.7688888888889,258.1 +127.66555555555556,93.23888888888888,127.66555555555556,96.825,127.66555555555556,91.80444444444444,258.2 +127.715,93.27499999999999,127.715,96.8625,127.715,91.84,258.3 +127.76444444444444,93.3111111111111,127.76444444444444,96.89999999999999,127.76444444444444,91.87555555555555,258.40000000000003 +127.81388888888888,93.34722222222221,127.81388888888888,96.9375,127.81388888888888,91.91111111111111,258.5 +127.86333333333333,93.38333333333333,127.86333333333333,96.975,127.86333333333333,91.94666666666667,258.6 +127.91277777777778,93.41944444444444,127.91277777777778,97.0125,127.91277777777778,91.98222222222222,258.7 +127.96222222222222,93.45555555555555,127.96222222222222,97.05,127.96222222222222,92.01777777777778,258.8 +128.01166666666666,93.49166666666666,128.01166666666666,97.08749999999999,128.01166666666666,92.05333333333333,258.90000000000003 +128.0611111111111,93.52777777777777,128.0611111111111,97.125,128.0611111111111,92.08888888888889,259.0 +128.11055555555555,93.56388888888888,128.11055555555555,97.1625,128.11055555555555,92.12444444444445,259.1 +128.16,93.6,128.16,97.2,128.16,92.16,259.2 +128.20944444444444,93.6361111111111,128.20944444444444,97.2375,128.20944444444444,92.19555555555556,259.3 +128.2588888888889,93.67222222222222,128.2588888888889,97.27499999999999,128.2588888888889,92.2311111111111,259.40000000000003 +128.30833333333334,93.70833333333333,128.30833333333334,97.3125,128.30833333333334,92.26666666666667,259.5 +128.35777777777778,93.74444444444444,128.35777777777778,97.35,128.35777777777778,92.30222222222223,259.6 +128.40722222222223,93.78055555555555,128.40722222222223,97.3875,128.40722222222223,92.33777777777777,259.7 +128.45666666666668,93.81666666666666,128.45666666666668,97.425,128.45666666666668,92.37333333333333,259.8 +128.5061111111111,93.85277777777777,128.5061111111111,97.46249999999999,128.5061111111111,92.40888888888888,259.90000000000003 +128.55555555555554,93.88888888888889,128.55555555555554,97.5,128.55555555555554,92.44444444444444,260.0 +128.605,93.925,128.605,97.5375,128.605,92.48,260.1 +128.65444444444444,93.96111111111111,128.65444444444444,97.575,128.65444444444444,92.51555555555555,260.2 +128.70388888888888,93.99722222222222,128.70388888888888,97.6125,128.70388888888888,92.55111111111111,260.3 +128.75333333333333,94.03333333333333,128.75333333333333,97.64999999999999,128.75333333333333,92.58666666666667,260.40000000000003 +128.80277777777778,94.06944444444443,128.80277777777778,97.6875,128.80277777777778,92.62222222222222,260.5 +128.85222222222222,94.10555555555554,128.85222222222222,97.725,128.85222222222222,92.65777777777778,260.6 +128.90166666666667,94.14166666666665,128.90166666666667,97.7625,128.90166666666667,92.69333333333333,260.7 +128.95111111111112,94.17777777777776,128.95111111111112,97.8,128.95111111111112,92.72888888888889,260.8 +129.00055555555556,94.21388888888887,129.00055555555556,97.83749999999999,129.00055555555556,92.76444444444445,260.90000000000003 +129.05,94.24999999999999,129.05,97.875,129.05,92.8,261.0 +129.09944444444443,94.2861111111111,129.09944444444443,97.9125,129.09944444444443,92.83555555555556,261.1 +129.14888888888888,94.32222222222221,129.14888888888888,97.95,129.14888888888888,92.8711111111111,261.2 +129.19833333333332,94.35833333333332,129.19833333333332,97.9875,129.19833333333332,92.90666666666667,261.3 +129.24777777777777,94.39444444444443,129.24777777777777,98.02499999999999,129.24777777777777,92.94222222222223,261.40000000000003 +129.29722222222222,94.43055555555554,129.29722222222222,98.0625,129.29722222222222,92.97777777777777,261.5 +129.34666666666666,94.46666666666665,129.34666666666666,98.1,129.34666666666666,93.01333333333334,261.6 +129.3961111111111,94.50277777777777,129.3961111111111,98.1375,129.3961111111111,93.04888888888888,261.7 +129.44555555555556,94.53888888888888,129.44555555555556,98.175,129.44555555555556,93.08444444444444,261.8 +129.495,94.57499999999999,129.495,98.21249999999999,129.495,93.12,261.90000000000003 +129.54444444444445,94.6111111111111,129.54444444444445,98.25,129.54444444444445,93.15555555555555,262.0 +129.5938888888889,94.64722222222221,129.5938888888889,98.2875,129.5938888888889,93.19111111111111,262.1 +129.64333333333335,94.68333333333332,129.64333333333335,98.325,129.64333333333335,93.22666666666667,262.2 +129.69277777777776,94.71944444444443,129.69277777777776,98.3625,129.69277777777776,93.26222222222222,262.3 +129.7422222222222,94.75555555555555,129.7422222222222,98.39999999999999,129.7422222222222,93.29777777777778,262.40000000000003 +129.79166666666666,94.79166666666666,129.79166666666666,98.4375,129.79166666666666,93.33333333333333,262.5 +129.8411111111111,94.82777777777777,129.8411111111111,98.475,129.8411111111111,93.36888888888889,262.6 +129.89055555555555,94.86388888888888,129.89055555555555,98.5125,129.89055555555555,93.40444444444445,262.7 +129.94,94.89999999999999,129.94,98.55,129.94,93.44,262.8 +129.98944444444444,94.9361111111111,129.98944444444444,98.58749999999999,129.98944444444444,93.47555555555556,262.90000000000003 +130.0388888888889,94.97222222222221,130.0388888888889,98.625,130.0388888888889,93.5111111111111,263.0 +130.08833333333334,95.00833333333333,130.08833333333334,98.6625,130.08833333333334,93.54666666666667,263.1 +130.13777777777779,95.04444444444444,130.13777777777779,98.7,130.13777777777779,93.58222222222223,263.2 +130.18722222222223,95.08055555555555,130.18722222222223,98.7375,130.18722222222223,93.61777777777777,263.3 +130.23666666666665,95.11666666666666,130.23666666666665,98.77499999999999,130.23666666666665,93.65333333333334,263.40000000000003 +130.2861111111111,95.15277777777777,130.2861111111111,98.8125,130.2861111111111,93.68888888888888,263.5 +130.33555555555554,95.18888888888888,130.33555555555554,98.85,130.33555555555554,93.72444444444444,263.6 +130.385,95.225,130.385,98.8875,130.385,93.76,263.7 +130.43444444444444,95.2611111111111,130.43444444444444,98.925,130.43444444444444,93.79555555555555,263.8 +130.48388888888888,95.29722222222222,130.48388888888888,98.96249999999999,130.48388888888888,93.83111111111111,263.90000000000003 +130.53333333333333,95.33333333333333,130.53333333333333,99.0,130.53333333333333,93.86666666666666,264.0 +130.58277777777778,95.36944444444444,130.58277777777778,99.0375,130.58277777777778,93.90222222222222,264.1 +130.63222222222223,95.40555555555555,130.63222222222223,99.075,130.63222222222223,93.93777777777778,264.2 +130.68166666666667,95.44166666666666,130.68166666666667,99.1125,130.68166666666667,93.97333333333333,264.3 +130.73111111111112,95.47777777777777,130.73111111111112,99.14999999999999,130.73111111111112,94.00888888888889,264.40000000000003 +130.78055555555557,95.51388888888889,130.78055555555557,99.1875,130.78055555555557,94.04444444444445,264.5 +130.82999999999998,95.55,130.82999999999998,99.225,130.82999999999998,94.08,264.6 +130.87944444444443,95.58611111111111,130.87944444444443,99.2625,130.87944444444443,94.11555555555556,264.7 +130.92888888888888,95.62222222222222,130.92888888888888,99.3,130.92888888888888,94.1511111111111,264.8 +130.97833333333332,95.65833333333333,130.97833333333332,99.33749999999999,130.97833333333332,94.18666666666667,264.90000000000003 +131.02777777777777,95.69444444444443,131.02777777777777,99.375,131.02777777777777,94.22222222222223,265.0 +131.07722222222222,95.73055555555554,131.07722222222222,99.4125,131.07722222222222,94.25777777777778,265.1 +131.12666666666667,95.76666666666665,131.12666666666667,99.45,131.12666666666667,94.29333333333334,265.2 +131.1761111111111,95.80277777777776,131.1761111111111,99.4875,131.1761111111111,94.32888888888888,265.3 +131.22555555555556,95.83888888888887,131.22555555555556,99.52499999999999,131.22555555555556,94.36444444444444,265.40000000000003 +131.275,95.87499999999999,131.275,99.5625,131.275,94.4,265.5 +131.32444444444445,95.9111111111111,131.32444444444445,99.6,131.32444444444445,94.43555555555555,265.6 +131.3738888888889,95.94722222222221,131.3738888888889,99.6375,131.3738888888889,94.47111111111111,265.7 +131.42333333333332,95.98333333333332,131.42333333333332,99.675,131.42333333333332,94.50666666666666,265.8 +131.47277777777776,96.01944444444443,131.47277777777776,99.71249999999999,131.47277777777776,94.54222222222222,265.90000000000003 +131.5222222222222,96.05555555555554,131.5222222222222,99.75,131.5222222222222,94.57777777777778,266.0 +131.57166666666666,96.09166666666665,131.57166666666666,99.7875,131.57166666666666,94.61333333333333,266.1 +131.6211111111111,96.12777777777777,131.6211111111111,99.825,131.6211111111111,94.64888888888889,266.2 +131.67055555555555,96.16388888888888,131.67055555555555,99.8625,131.67055555555555,94.68444444444444,266.3 +131.72,96.19999999999999,131.72,99.89999999999999,131.72,94.72,266.40000000000003 +131.76944444444445,96.2361111111111,131.76944444444445,99.9375,131.76944444444445,94.75555555555556,266.5 +131.8188888888889,96.27222222222221,131.8188888888889,99.975,131.8188888888889,94.7911111111111,266.6 +131.86833333333334,96.30833333333332,131.86833333333334,100.0125,131.86833333333334,94.82666666666667,266.7 +131.9177777777778,96.34444444444443,131.9177777777778,100.05,131.9177777777778,94.86222222222223,266.8 +131.96722222222223,96.38055555555555,131.96722222222223,100.08749999999999,131.96722222222223,94.89777777777778,266.90000000000003 +132.01666666666665,96.41666666666666,132.01666666666665,100.125,132.01666666666665,94.93333333333334,267.0 +132.0661111111111,96.45277777777777,132.0661111111111,100.1625,132.0661111111111,94.96888888888888,267.1 +132.11555555555555,96.48888888888888,132.11555555555555,100.2,132.11555555555555,95.00444444444445,267.2 +132.165,96.52499999999999,132.165,100.2375,132.165,95.04,267.3 +132.21444444444444,96.5611111111111,132.21444444444444,100.27499999999999,132.21444444444444,95.07555555555555,267.40000000000003 +132.26388888888889,96.59722222222221,132.26388888888889,100.3125,132.26388888888889,95.11111111111111,267.5 +132.31333333333333,96.63333333333333,132.31333333333333,100.35,132.31333333333333,95.14666666666666,267.6 +132.36277777777778,96.66944444444444,132.36277777777778,100.3875,132.36277777777778,95.18222222222222,267.7 +132.41222222222223,96.70555555555555,132.41222222222223,100.425,132.41222222222223,95.21777777777778,267.8 +132.46166666666667,96.74166666666666,132.46166666666667,100.46249999999999,132.46166666666667,95.25333333333333,267.90000000000003 +132.51111111111112,96.77777777777777,132.51111111111112,100.5,132.51111111111112,95.28888888888889,268.0 +132.56055555555557,96.81388888888888,132.56055555555557,100.5375,132.56055555555557,95.32444444444444,268.1 +132.60999999999999,96.85,132.60999999999999,100.575,132.60999999999999,95.36,268.2 +132.65944444444443,96.8861111111111,132.65944444444443,100.6125,132.65944444444443,95.39555555555556,268.3 +132.70888888888888,96.92222222222222,132.70888888888888,100.64999999999999,132.70888888888888,95.43111111111111,268.40000000000003 +132.75833333333333,96.95833333333333,132.75833333333333,100.6875,132.75833333333333,95.46666666666667,268.5 +132.80777777777777,96.99444444444444,132.80777777777777,100.725,132.80777777777777,95.50222222222222,268.6 +132.85722222222222,97.03055555555555,132.85722222222222,100.7625,132.85722222222222,95.53777777777778,268.7 +132.90666666666667,97.06666666666666,132.90666666666667,100.8,132.90666666666667,95.57333333333334,268.8 +132.9561111111111,97.10277777777777,132.9561111111111,100.83749999999999,132.9561111111111,95.60888888888888,268.90000000000003 +133.00555555555556,97.13888888888889,133.00555555555556,100.875,133.00555555555556,95.64444444444445,269.0 +133.055,97.175,133.055,100.9125,133.055,95.68,269.1 +133.10444444444445,97.21111111111111,133.10444444444445,100.95,133.10444444444445,95.71555555555555,269.2 +133.1538888888889,97.24722222222222,133.1538888888889,100.9875,133.1538888888889,95.75111111111111,269.3 +133.20333333333332,97.28333333333332,133.20333333333332,101.02499999999999,133.20333333333332,95.78666666666666,269.40000000000003 +133.25277777777777,97.31944444444443,133.25277777777777,101.0625,133.25277777777777,95.82222222222222,269.5 +133.3022222222222,97.35555555555554,133.3022222222222,101.1,133.3022222222222,95.85777777777778,269.6 +133.35166666666666,97.39166666666665,133.35166666666666,101.1375,133.35166666666666,95.89333333333333,269.7 +133.4011111111111,97.42777777777776,133.4011111111111,101.175,133.4011111111111,95.92888888888889,269.8 +133.45055555555555,97.46388888888887,133.45055555555555,101.21249999999999,133.45055555555555,95.96444444444444,269.90000000000003 +133.5,97.49999999999999,133.5,101.25,133.5,96.0,270.0 +133.54944444444445,97.5361111111111,133.54944444444445,101.2875,133.54944444444445,96.03555555555556,270.1 +133.5988888888889,97.57222222222221,133.5988888888889,101.325,133.5988888888889,96.07111111111111,270.2 +133.64833333333334,97.60833333333332,133.64833333333334,101.3625,133.64833333333334,96.10666666666667,270.3 +133.6977777777778,97.64444444444443,133.6977777777778,101.39999999999999,133.6977777777778,96.14222222222222,270.40000000000003 +133.74722222222223,97.68055555555554,133.74722222222223,101.4375,133.74722222222223,96.17777777777778,270.5 +133.79666666666665,97.71666666666665,133.79666666666665,101.475,133.79666666666665,96.21333333333334,270.6 +133.8461111111111,97.75277777777777,133.8461111111111,101.5125,133.8461111111111,96.24888888888889,270.7 +133.89555555555555,97.78888888888888,133.89555555555555,101.55,133.89555555555555,96.28444444444445,270.8 +133.945,97.82499999999999,133.945,101.58749999999999,133.945,96.32,270.90000000000003 +133.99444444444444,97.8611111111111,133.99444444444444,101.625,133.99444444444444,96.35555555555555,271.0 +134.0438888888889,97.89722222222221,134.0438888888889,101.6625,134.0438888888889,96.39111111111112,271.1 +134.09333333333333,97.93333333333332,134.09333333333333,101.7,134.09333333333333,96.42666666666666,271.2 +134.14277777777778,97.96944444444443,134.14277777777778,101.7375,134.14277777777778,96.46222222222222,271.3 +134.19222222222223,98.00555555555555,134.19222222222223,101.77499999999999,134.19222222222223,96.49777777777778,271.40000000000003 +134.24166666666667,98.04166666666666,134.24166666666667,101.8125,134.24166666666667,96.53333333333333,271.5 +134.29111111111112,98.07777777777777,134.29111111111112,101.85,134.29111111111112,96.56888888888889,271.6 +134.34055555555554,98.11388888888888,134.34055555555554,101.8875,134.34055555555554,96.60444444444444,271.7 +134.39,98.14999999999999,134.39,101.925,134.39,96.64,271.8 +134.43944444444443,98.1861111111111,134.43944444444443,101.96249999999999,134.43944444444443,96.67555555555556,271.90000000000003 +134.48888888888888,98.22222222222221,134.48888888888888,102.0,134.48888888888888,96.71111111111111,272.0 +134.53833333333333,98.25833333333333,134.53833333333333,102.0375,134.53833333333333,96.74666666666667,272.1 +134.58777777777777,98.29444444444444,134.58777777777777,102.075,134.58777777777777,96.78222222222222,272.2 +134.63722222222222,98.33055555555555,134.63722222222222,102.1125,134.63722222222222,96.81777777777778,272.3 +134.68666666666667,98.36666666666666,134.68666666666667,102.14999999999999,134.68666666666667,96.85333333333334,272.40000000000003 +134.73611111111111,98.40277777777777,134.73611111111111,102.1875,134.73611111111111,96.88888888888889,272.5 +134.78555555555556,98.43888888888888,134.78555555555556,102.225,134.78555555555556,96.92444444444445,272.6 +134.835,98.475,134.835,102.2625,134.835,96.96,272.7 +134.88444444444445,98.5111111111111,134.88444444444445,102.3,134.88444444444445,96.99555555555555,272.8 +134.93388888888887,98.54722222222222,134.93388888888887,102.33749999999999,134.93388888888887,97.03111111111112,272.90000000000003 +134.98333333333332,98.58333333333333,134.98333333333332,102.375,134.98333333333332,97.06666666666666,273.0 +135.03277777777777,98.61944444444444,135.03277777777777,102.4125,135.03277777777777,97.10222222222222,273.1 +135.0822222222222,98.65555555555555,135.0822222222222,102.45,135.0822222222222,97.13777777777777,273.2 +135.13166666666666,98.69166666666666,135.13166666666666,102.4875,135.13166666666666,97.17333333333333,273.3 +135.1811111111111,98.72777777777777,135.1811111111111,102.52499999999999,135.1811111111111,97.2088888888889,273.40000000000003 +135.23055555555555,98.76388888888889,135.23055555555555,102.5625,135.23055555555555,97.24444444444444,273.5 +135.28,98.8,135.28,102.6,135.28,97.28,273.6 +135.32944444444445,98.83611111111111,135.32944444444445,102.6375,135.32944444444445,97.31555555555556,273.7 +135.3788888888889,98.87222222222222,135.3788888888889,102.675,135.3788888888889,97.35111111111111,273.8 +135.42833333333334,98.90833333333332,135.42833333333334,102.71249999999999,135.42833333333334,97.38666666666667,273.90000000000003 +135.4777777777778,98.94444444444443,135.4777777777778,102.75,135.4777777777778,97.42222222222222,274.0 +135.5272222222222,98.98055555555554,135.5272222222222,102.7875,135.5272222222222,97.45777777777778,274.1 +135.57666666666665,99.01666666666665,135.57666666666665,102.825,135.57666666666665,97.49333333333334,274.2 +135.6261111111111,99.05277777777776,135.6261111111111,102.8625,135.6261111111111,97.52888888888889,274.3 +135.67555555555555,99.08888888888887,135.67555555555555,102.89999999999999,135.67555555555555,97.56444444444445,274.40000000000003 +135.725,99.12499999999999,135.725,102.9375,135.725,97.6,274.5 +135.77444444444444,99.1611111111111,135.77444444444444,102.975,135.77444444444444,97.63555555555556,274.6 +135.8238888888889,99.19722222222221,135.8238888888889,103.0125,135.8238888888889,97.67111111111112,274.7 +135.87333333333333,99.23333333333332,135.87333333333333,103.05,135.87333333333333,97.70666666666666,274.8 +135.92277777777778,99.26944444444443,135.92277777777778,103.08749999999999,135.92277777777778,97.74222222222222,274.90000000000003 +135.97222222222223,99.30555555555554,135.97222222222223,103.125,135.97222222222223,97.77777777777777,275.0 +136.02166666666668,99.34166666666665,136.02166666666668,103.1625,136.02166666666668,97.81333333333333,275.1 +136.07111111111112,99.37777777777777,136.07111111111112,103.2,136.07111111111112,97.8488888888889,275.2 +136.12055555555554,99.41388888888888,136.12055555555554,103.2375,136.12055555555554,97.88444444444444,275.3 +136.17,99.44999999999999,136.17,103.27499999999999,136.17,97.92,275.40000000000003 +136.21944444444443,99.4861111111111,136.21944444444443,103.3125,136.21944444444443,97.95555555555555,275.5 +136.26888888888888,99.52222222222221,136.26888888888888,103.35,136.26888888888888,97.99111111111111,275.6 +136.31833333333333,99.55833333333332,136.31833333333333,103.3875,136.31833333333333,98.02666666666667,275.7 +136.36777777777777,99.59444444444443,136.36777777777777,103.425,136.36777777777777,98.06222222222222,275.8 +136.41722222222222,99.63055555555555,136.41722222222222,103.46249999999999,136.41722222222222,98.09777777777778,275.90000000000003 +136.46666666666667,99.66666666666666,136.46666666666667,103.5,136.46666666666667,98.13333333333334,276.0 +136.51611111111112,99.70277777777777,136.51611111111112,103.5375,136.51611111111112,98.16888888888889,276.1 +136.56555555555556,99.73888888888888,136.56555555555556,103.575,136.56555555555556,98.20444444444445,276.2 +136.615,99.77499999999999,136.615,103.6125,136.615,98.24,276.3 +136.66444444444446,99.8111111111111,136.66444444444446,103.64999999999999,136.66444444444446,98.27555555555556,276.40000000000003 +136.71388888888887,99.84722222222221,136.71388888888887,103.6875,136.71388888888887,98.31111111111112,276.5 +136.76333333333332,99.88333333333333,136.76333333333332,103.725,136.76333333333332,98.34666666666666,276.6 +136.81277777777777,99.91944444444444,136.81277777777777,103.7625,136.81277777777777,98.38222222222223,276.7 +136.86222222222221,99.95555555555555,136.86222222222221,103.8,136.86222222222221,98.41777777777777,276.8 +136.91166666666666,99.99166666666666,136.91166666666666,103.83749999999999,136.91166666666666,98.45333333333333,276.90000000000003 +136.9611111111111,100.02777777777777,136.9611111111111,103.875,136.9611111111111,98.4888888888889,277.0 +137.01055555555556,100.06388888888888,137.01055555555556,103.9125,137.01055555555556,98.52444444444444,277.1 +137.06,100.1,137.06,103.95,137.06,98.56,277.2 +137.10944444444445,100.1361111111111,137.10944444444445,103.9875,137.10944444444445,98.59555555555555,277.3 +137.1588888888889,100.17222222222222,137.1588888888889,104.02499999999999,137.1588888888889,98.63111111111111,277.40000000000003 +137.20833333333334,100.20833333333333,137.20833333333334,104.0625,137.20833333333334,98.66666666666667,277.5 +137.2577777777778,100.24444444444444,137.2577777777778,104.1,137.2577777777778,98.70222222222222,277.6 +137.3072222222222,100.28055555555555,137.3072222222222,104.1375,137.3072222222222,98.73777777777778,277.7 +137.35666666666665,100.31666666666666,137.35666666666665,104.175,137.35666666666665,98.77333333333333,277.8 +137.4061111111111,100.35277777777777,137.4061111111111,104.21249999999999,137.4061111111111,98.80888888888889,277.90000000000003 +137.45555555555555,100.38888888888889,137.45555555555555,104.25,137.45555555555555,98.84444444444445,278.0 +137.505,100.425,137.505,104.2875,137.505,98.88,278.1 +137.55444444444444,100.46111111111111,137.55444444444444,104.325,137.55444444444444,98.91555555555556,278.2 +137.6038888888889,100.4972222222222,137.6038888888889,104.3625,137.6038888888889,98.95111111111112,278.3 +137.65333333333334,100.53333333333332,137.65333333333334,104.39999999999999,137.65333333333334,98.98666666666666,278.40000000000003 +137.70277777777778,100.56944444444443,137.70277777777778,104.4375,137.70277777777778,99.02222222222223,278.5 +137.75222222222223,100.60555555555554,137.75222222222223,104.475,137.75222222222223,99.05777777777777,278.6 +137.80166666666668,100.64166666666665,137.80166666666668,104.5125,137.80166666666668,99.09333333333333,278.7 +137.8511111111111,100.67777777777776,137.8511111111111,104.55,137.8511111111111,99.1288888888889,278.8 +137.90055555555554,100.71388888888887,137.90055555555554,104.58749999999999,137.90055555555554,99.16444444444444,278.90000000000003 +137.95,100.74999999999999,137.95,104.625,137.95,99.2,279.0 +137.99944444444444,100.7861111111111,137.99944444444444,104.6625,137.99944444444444,99.23555555555555,279.1 +138.04888888888888,100.82222222222221,138.04888888888888,104.7,138.04888888888888,99.27111111111111,279.2 +138.09833333333333,100.85833333333332,138.09833333333333,104.7375,138.09833333333333,99.30666666666667,279.3 +138.14777777777778,100.89444444444443,138.14777777777778,104.77499999999999,138.14777777777778,99.34222222222222,279.40000000000003 +138.19722222222222,100.93055555555554,138.19722222222222,104.8125,138.19722222222222,99.37777777777778,279.5 +138.24666666666667,100.96666666666665,138.24666666666667,104.85,138.24666666666667,99.41333333333333,279.6 +138.29611111111112,101.00277777777777,138.29611111111112,104.8875,138.29611111111112,99.44888888888889,279.7 +138.34555555555556,101.03888888888888,138.34555555555556,104.925,138.34555555555556,99.48444444444445,279.8 +138.395,101.07499999999999,138.395,104.96249999999999,138.395,99.52,279.90000000000003 +138.44444444444443,101.1111111111111,138.44444444444443,105.0,138.44444444444443,99.55555555555556,280.0 +138.49388888888888,101.14722222222221,138.49388888888888,105.0375,138.49388888888888,99.5911111111111,280.1 +138.54333333333332,101.18333333333332,138.54333333333332,105.075,138.54333333333332,99.62666666666667,280.2 +138.59277777777777,101.21944444444443,138.59277777777777,105.1125,138.59277777777777,99.66222222222223,280.3 +138.64222222222222,101.25555555555555,138.64222222222222,105.14999999999999,138.64222222222222,99.69777777777777,280.40000000000003 +138.69166666666666,101.29166666666666,138.69166666666666,105.1875,138.69166666666666,99.73333333333333,280.5 +138.7411111111111,101.32777777777777,138.7411111111111,105.225,138.7411111111111,99.7688888888889,280.6 +138.79055555555556,101.36388888888888,138.79055555555556,105.2625,138.79055555555556,99.80444444444444,280.7 +138.84,101.39999999999999,138.84,105.3,138.84,99.84,280.8 +138.88944444444445,101.4361111111111,138.88944444444445,105.33749999999999,138.88944444444445,99.87555555555555,280.90000000000003 +138.9388888888889,101.47222222222221,138.9388888888889,105.375,138.9388888888889,99.91111111111111,281.0 +138.98833333333334,101.50833333333333,138.98833333333334,105.4125,138.98833333333334,99.94666666666667,281.1 +139.03777777777776,101.54444444444444,139.03777777777776,105.45,139.03777777777776,99.98222222222222,281.2 +139.0872222222222,101.58055555555555,139.0872222222222,105.4875,139.0872222222222,100.01777777777778,281.3 +139.13666666666666,101.61666666666666,139.13666666666666,105.52499999999999,139.13666666666666,100.05333333333333,281.40000000000003 +139.1861111111111,101.65277777777777,139.1861111111111,105.5625,139.1861111111111,100.08888888888889,281.5 +139.23555555555555,101.68888888888888,139.23555555555555,105.6,139.23555555555555,100.12444444444445,281.6 +139.285,101.725,139.285,105.6375,139.285,100.16,281.7 +139.33444444444444,101.7611111111111,139.33444444444444,105.675,139.33444444444444,100.19555555555556,281.8 +139.3838888888889,101.79722222222222,139.3838888888889,105.71249999999999,139.3838888888889,100.2311111111111,281.90000000000003 +139.43333333333334,101.83333333333333,139.43333333333334,105.75,139.43333333333334,100.26666666666667,282.0 +139.48277777777778,101.86944444444444,139.48277777777778,105.7875,139.48277777777778,100.30222222222223,282.1 +139.53222222222223,101.90555555555555,139.53222222222223,105.825,139.53222222222223,100.33777777777777,282.2 +139.58166666666668,101.94166666666666,139.58166666666668,105.8625,139.58166666666668,100.37333333333333,282.3 +139.6311111111111,101.97777777777777,139.6311111111111,105.89999999999999,139.6311111111111,100.40888888888888,282.40000000000003 +139.68055555555554,102.01388888888889,139.68055555555554,105.9375,139.68055555555554,100.44444444444444,282.5 +139.73,102.05,139.73,105.975,139.73,100.48,282.6 +139.77944444444444,102.08611111111111,139.77944444444444,106.0125,139.77944444444444,100.51555555555555,282.7 +139.82888888888888,102.1222222222222,139.82888888888888,106.05,139.82888888888888,100.55111111111111,282.8 +139.87833333333333,102.15833333333332,139.87833333333333,106.08749999999999,139.87833333333333,100.58666666666667,282.90000000000003 +139.92777777777778,102.19444444444443,139.92777777777778,106.125,139.92777777777778,100.62222222222222,283.0 +139.97722222222222,102.23055555555554,139.97722222222222,106.1625,139.97722222222222,100.65777777777778,283.1 +140.02666666666667,102.26666666666665,140.02666666666667,106.2,140.02666666666667,100.69333333333333,283.2 +140.07611111111112,102.30277777777776,140.07611111111112,106.2375,140.07611111111112,100.72888888888889,283.3 +140.12555555555556,102.33888888888887,140.12555555555556,106.27499999999999,140.12555555555556,100.76444444444445,283.40000000000003 +140.175,102.37499999999999,140.175,106.3125,140.175,100.8,283.5 +140.22444444444443,102.4111111111111,140.22444444444443,106.35,140.22444444444443,100.83555555555556,283.6 +140.27388888888888,102.44722222222221,140.27388888888888,106.3875,140.27388888888888,100.8711111111111,283.7 +140.32333333333332,102.48333333333332,140.32333333333332,106.425,140.32333333333332,100.90666666666667,283.8 +140.37277777777777,102.51944444444443,140.37277777777777,106.46249999999999,140.37277777777777,100.94222222222223,283.90000000000003 +140.42222222222222,102.55555555555554,140.42222222222222,106.5,140.42222222222222,100.97777777777777,284.0 +140.47166666666666,102.59166666666665,140.47166666666666,106.5375,140.47166666666666,101.01333333333334,284.1 +140.5211111111111,102.62777777777777,140.5211111111111,106.575,140.5211111111111,101.04888888888888,284.2 +140.57055555555556,102.66388888888888,140.57055555555556,106.6125,140.57055555555556,101.08444444444444,284.3 +140.62,102.69999999999999,140.62,106.64999999999999,140.62,101.12,284.40000000000003 +140.66944444444445,102.7361111111111,140.66944444444445,106.6875,140.66944444444445,101.15555555555555,284.5 +140.7188888888889,102.77222222222221,140.7188888888889,106.725,140.7188888888889,101.19111111111111,284.6 +140.76833333333335,102.80833333333332,140.76833333333335,106.7625,140.76833333333335,101.22666666666667,284.7 +140.81777777777776,102.84444444444443,140.81777777777776,106.8,140.81777777777776,101.26222222222222,284.8 +140.8672222222222,102.88055555555555,140.8672222222222,106.83749999999999,140.8672222222222,101.29777777777778,284.90000000000003 +140.91666666666666,102.91666666666666,140.91666666666666,106.875,140.91666666666666,101.33333333333333,285.0 +140.9661111111111,102.95277777777777,140.9661111111111,106.9125,140.9661111111111,101.36888888888889,285.1 +141.01555555555555,102.98888888888888,141.01555555555555,106.95,141.01555555555555,101.40444444444445,285.2 +141.065,103.02499999999999,141.065,106.9875,141.065,101.44,285.3 +141.11444444444444,103.0611111111111,141.11444444444444,107.02499999999999,141.11444444444444,101.47555555555556,285.40000000000003 +141.1638888888889,103.09722222222221,141.1638888888889,107.0625,141.1638888888889,101.5111111111111,285.5 +141.21333333333334,103.13333333333333,141.21333333333334,107.1,141.21333333333334,101.54666666666667,285.6 +141.26277777777779,103.16944444444444,141.26277777777779,107.1375,141.26277777777779,101.58222222222223,285.7 +141.31222222222223,103.20555555555555,141.31222222222223,107.175,141.31222222222223,101.61777777777777,285.8 +141.36166666666665,103.24166666666666,141.36166666666665,107.21249999999999,141.36166666666665,101.65333333333334,285.90000000000003 +141.4111111111111,103.27777777777777,141.4111111111111,107.25,141.4111111111111,101.68888888888888,286.0 +141.46055555555554,103.31388888888888,141.46055555555554,107.2875,141.46055555555554,101.72444444444444,286.1 +141.51,103.35,141.51,107.325,141.51,101.76,286.2 +141.55944444444444,103.3861111111111,141.55944444444444,107.3625,141.55944444444444,101.79555555555555,286.3 +141.60888888888888,103.42222222222222,141.60888888888888,107.39999999999999,141.60888888888888,101.83111111111111,286.40000000000003 +141.65833333333333,103.45833333333333,141.65833333333333,107.4375,141.65833333333333,101.86666666666666,286.5 +141.70777777777778,103.49444444444444,141.70777777777778,107.475,141.70777777777778,101.90222222222222,286.6 +141.75722222222223,103.53055555555555,141.75722222222223,107.5125,141.75722222222223,101.93777777777778,286.7 +141.80666666666667,103.56666666666666,141.80666666666667,107.55,141.80666666666667,101.97333333333333,286.8 +141.85611111111112,103.60277777777777,141.85611111111112,107.58749999999999,141.85611111111112,102.00888888888889,286.90000000000003 +141.90555555555557,103.63888888888889,141.90555555555557,107.625,141.90555555555557,102.04444444444445,287.0 +141.95499999999998,103.675,141.95499999999998,107.6625,141.95499999999998,102.08,287.1 +142.00444444444443,103.7111111111111,142.00444444444443,107.7,142.00444444444443,102.11555555555556,287.2 +142.05388888888888,103.7472222222222,142.05388888888888,107.7375,142.05388888888888,102.1511111111111,287.3 +142.10333333333332,103.78333333333332,142.10333333333332,107.77499999999999,142.10333333333332,102.18666666666667,287.40000000000003 +142.15277777777777,103.81944444444443,142.15277777777777,107.8125,142.15277777777777,102.22222222222223,287.5 +142.20222222222222,103.85555555555554,142.20222222222222,107.85,142.20222222222222,102.25777777777778,287.6 +142.25166666666667,103.89166666666665,142.25166666666667,107.8875,142.25166666666667,102.29333333333334,287.7 +142.3011111111111,103.92777777777776,142.3011111111111,107.925,142.3011111111111,102.32888888888888,287.8 +142.35055555555556,103.96388888888887,142.35055555555556,107.96249999999999,142.35055555555556,102.36444444444444,287.90000000000003 +142.4,103.99999999999999,142.4,108.0,142.4,102.4,288.0 +142.44944444444445,104.0361111111111,142.44944444444445,108.0375,142.44944444444445,102.43555555555555,288.1 +142.4988888888889,104.07222222222221,142.4988888888889,108.075,142.4988888888889,102.47111111111111,288.2 +142.54833333333332,104.10833333333332,142.54833333333332,108.1125,142.54833333333332,102.50666666666666,288.3 +142.59777777777776,104.14444444444443,142.59777777777776,108.14999999999999,142.59777777777776,102.54222222222222,288.40000000000003 +142.6472222222222,104.18055555555554,142.6472222222222,108.1875,142.6472222222222,102.57777777777778,288.5 +142.69666666666666,104.21666666666665,142.69666666666666,108.225,142.69666666666666,102.61333333333333,288.6 +142.7461111111111,104.25277777777777,142.7461111111111,108.2625,142.7461111111111,102.64888888888889,288.7 +142.79555555555555,104.28888888888888,142.79555555555555,108.3,142.79555555555555,102.68444444444444,288.8 +142.845,104.32499999999999,142.845,108.33749999999999,142.845,102.72,288.90000000000003 +142.89444444444445,104.3611111111111,142.89444444444445,108.375,142.89444444444445,102.75555555555556,289.0 +142.9438888888889,104.39722222222221,142.9438888888889,108.4125,142.9438888888889,102.7911111111111,289.1 +142.99333333333334,104.43333333333332,142.99333333333334,108.45,142.99333333333334,102.82666666666667,289.2 +143.0427777777778,104.46944444444443,143.0427777777778,108.4875,143.0427777777778,102.86222222222223,289.3 +143.09222222222223,104.50555555555555,143.09222222222223,108.52499999999999,143.09222222222223,102.89777777777778,289.40000000000003 +143.14166666666665,104.54166666666666,143.14166666666665,108.5625,143.14166666666665,102.93333333333334,289.5 +143.1911111111111,104.57777777777777,143.1911111111111,108.6,143.1911111111111,102.96888888888888,289.6 +143.24055555555555,104.61388888888888,143.24055555555555,108.6375,143.24055555555555,103.00444444444445,289.7 +143.29,104.64999999999999,143.29,108.675,143.29,103.04,289.8 +143.33944444444444,104.6861111111111,143.33944444444444,108.71249999999999,143.33944444444444,103.07555555555555,289.90000000000003 +143.38888888888889,104.72222222222221,143.38888888888889,108.75,143.38888888888889,103.11111111111111,290.0 +143.43833333333333,104.75833333333333,143.43833333333333,108.7875,143.43833333333333,103.14666666666666,290.1 +143.48777777777778,104.79444444444444,143.48777777777778,108.825,143.48777777777778,103.18222222222222,290.2 +143.53722222222223,104.83055555555555,143.53722222222223,108.8625,143.53722222222223,103.21777777777778,290.3 +143.58666666666667,104.86666666666666,143.58666666666667,108.89999999999999,143.58666666666667,103.25333333333333,290.40000000000003 +143.63611111111112,104.90277777777777,143.63611111111112,108.9375,143.63611111111112,103.28888888888889,290.5 +143.68555555555557,104.93888888888888,143.68555555555557,108.975,143.68555555555557,103.32444444444444,290.6 +143.73499999999999,104.975,143.73499999999999,109.0125,143.73499999999999,103.36,290.7 +143.78444444444443,105.0111111111111,143.78444444444443,109.05,143.78444444444443,103.39555555555556,290.8 +143.83388888888888,105.04722222222222,143.83388888888888,109.08749999999999,143.83388888888888,103.43111111111111,290.90000000000003 +143.88333333333333,105.08333333333333,143.88333333333333,109.125,143.88333333333333,103.46666666666667,291.0 +143.93277777777777,105.11944444444444,143.93277777777777,109.1625,143.93277777777777,103.50222222222222,291.1 +143.98222222222222,105.15555555555555,143.98222222222222,109.2,143.98222222222222,103.53777777777778,291.2 +144.03166666666667,105.19166666666666,144.03166666666667,109.2375,144.03166666666667,103.57333333333334,291.3 +144.0811111111111,105.22777777777777,144.0811111111111,109.27499999999999,144.0811111111111,103.60888888888888,291.40000000000003 +144.13055555555556,105.26388888888889,144.13055555555556,109.3125,144.13055555555556,103.64444444444445,291.5 +144.18,105.3,144.18,109.35,144.18,103.68,291.6 +144.22944444444445,105.3361111111111,144.22944444444445,109.3875,144.22944444444445,103.71555555555555,291.7 +144.2788888888889,105.3722222222222,144.2788888888889,109.425,144.2788888888889,103.75111111111111,291.8 +144.32833333333332,105.40833333333332,144.32833333333332,109.46249999999999,144.32833333333332,103.78666666666666,291.90000000000003 +144.37777777777777,105.44444444444443,144.37777777777777,109.5,144.37777777777777,103.82222222222222,292.0 +144.4272222222222,105.48055555555554,144.4272222222222,109.5375,144.4272222222222,103.85777777777778,292.1 +144.47666666666666,105.51666666666665,144.47666666666666,109.575,144.47666666666666,103.89333333333333,292.2 +144.5261111111111,105.55277777777776,144.5261111111111,109.6125,144.5261111111111,103.92888888888889,292.3 +144.57555555555555,105.58888888888887,144.57555555555555,109.64999999999999,144.57555555555555,103.96444444444444,292.40000000000003 +144.625,105.62499999999999,144.625,109.6875,144.625,104.0,292.5 +144.67444444444445,105.6611111111111,144.67444444444445,109.725,144.67444444444445,104.03555555555556,292.6 +144.7238888888889,105.69722222222221,144.7238888888889,109.7625,144.7238888888889,104.07111111111111,292.7 +144.77333333333334,105.73333333333332,144.77333333333334,109.8,144.77333333333334,104.10666666666667,292.8 +144.8227777777778,105.76944444444443,144.8227777777778,109.83749999999999,144.8227777777778,104.14222222222222,292.90000000000003 +144.8722222222222,105.80555555555554,144.8722222222222,109.875,144.8722222222222,104.17777777777778,293.0 +144.92166666666665,105.84166666666665,144.92166666666665,109.9125,144.92166666666665,104.21333333333334,293.1 +144.9711111111111,105.87777777777777,144.9711111111111,109.95,144.9711111111111,104.24888888888889,293.2 +145.02055555555555,105.91388888888888,145.02055555555555,109.9875,145.02055555555555,104.28444444444445,293.3 +145.07,105.94999999999999,145.07,110.02499999999999,145.07,104.32,293.40000000000003 +145.11944444444444,105.9861111111111,145.11944444444444,110.0625,145.11944444444444,104.35555555555555,293.5 +145.1688888888889,106.02222222222221,145.1688888888889,110.1,145.1688888888889,104.39111111111112,293.6 +145.21833333333333,106.05833333333332,145.21833333333333,110.1375,145.21833333333333,104.42666666666666,293.7 +145.26777777777778,106.09444444444443,145.26777777777778,110.175,145.26777777777778,104.46222222222222,293.8 +145.31722222222223,106.13055555555555,145.31722222222223,110.21249999999999,145.31722222222223,104.49777777777778,293.90000000000003 +145.36666666666667,106.16666666666666,145.36666666666667,110.25,145.36666666666667,104.53333333333333,294.0 +145.41611111111112,106.20277777777777,145.41611111111112,110.2875,145.41611111111112,104.56888888888889,294.1 +145.46555555555554,106.23888888888888,145.46555555555554,110.325,145.46555555555554,104.60444444444444,294.2 +145.515,106.27499999999999,145.515,110.3625,145.515,104.64,294.3 +145.56444444444443,106.3111111111111,145.56444444444443,110.39999999999999,145.56444444444443,104.67555555555556,294.40000000000003 +145.61388888888888,106.34722222222221,145.61388888888888,110.4375,145.61388888888888,104.71111111111111,294.5 +145.66333333333333,106.38333333333333,145.66333333333333,110.475,145.66333333333333,104.74666666666667,294.6 +145.71277777777777,106.41944444444444,145.71277777777777,110.5125,145.71277777777777,104.78222222222222,294.7 +145.76222222222222,106.45555555555555,145.76222222222222,110.55,145.76222222222222,104.81777777777778,294.8 +145.81166666666667,106.49166666666666,145.81166666666667,110.58749999999999,145.81166666666667,104.85333333333334,294.90000000000003 +145.86111111111111,106.52777777777777,145.86111111111111,110.625,145.86111111111111,104.88888888888889,295.0 +145.91055555555556,106.56388888888888,145.91055555555556,110.6625,145.91055555555556,104.92444444444445,295.1 +145.96,106.6,145.96,110.7,145.96,104.96,295.2 +146.00944444444445,106.6361111111111,146.00944444444445,110.7375,146.00944444444445,104.99555555555555,295.3 +146.05888888888887,106.67222222222222,146.05888888888887,110.77499999999999,146.05888888888887,105.03111111111112,295.40000000000003 +146.10833333333332,106.70833333333333,146.10833333333332,110.8125,146.10833333333332,105.06666666666666,295.5 +146.15777777777777,106.74444444444444,146.15777777777777,110.85,146.15777777777777,105.10222222222222,295.6 +146.2072222222222,106.78055555555555,146.2072222222222,110.8875,146.2072222222222,105.13777777777777,295.7 +146.25666666666666,106.81666666666666,146.25666666666666,110.925,146.25666666666666,105.17333333333333,295.8 +146.3061111111111,106.85277777777777,146.3061111111111,110.96249999999999,146.3061111111111,105.2088888888889,295.90000000000003 +146.35555555555555,106.88888888888889,146.35555555555555,111.0,146.35555555555555,105.24444444444444,296.0 +146.405,106.92499999999998,146.405,111.0375,146.405,105.28,296.1 +146.45444444444445,106.9611111111111,146.45444444444445,111.075,146.45444444444445,105.31555555555556,296.2 +146.5038888888889,106.9972222222222,146.5038888888889,111.1125,146.5038888888889,105.35111111111111,296.3 +146.55333333333334,107.03333333333332,146.55333333333334,111.14999999999999,146.55333333333334,105.38666666666667,296.40000000000003 +146.6027777777778,107.06944444444443,146.6027777777778,111.1875,146.6027777777778,105.42222222222222,296.5 +146.6522222222222,107.10555555555554,146.6522222222222,111.225,146.6522222222222,105.45777777777778,296.6 +146.70166666666665,107.14166666666665,146.70166666666665,111.2625,146.70166666666665,105.49333333333334,296.7 +146.7511111111111,107.17777777777776,146.7511111111111,111.3,146.7511111111111,105.52888888888889,296.8 +146.80055555555555,107.21388888888887,146.80055555555555,111.33749999999999,146.80055555555555,105.56444444444445,296.90000000000003 +146.85,107.24999999999999,146.85,111.375,146.85,105.6,297.0 +146.89944444444444,107.2861111111111,146.89944444444444,111.4125,146.89944444444444,105.63555555555556,297.1 +146.9488888888889,107.32222222222221,146.9488888888889,111.45,146.9488888888889,105.67111111111112,297.2 +146.99833333333333,107.35833333333332,146.99833333333333,111.4875,146.99833333333333,105.70666666666666,297.3 +147.04777777777778,107.39444444444443,147.04777777777778,111.52499999999999,147.04777777777778,105.74222222222222,297.40000000000003 +147.09722222222223,107.43055555555554,147.09722222222223,111.5625,147.09722222222223,105.77777777777777,297.5 +147.14666666666668,107.46666666666665,147.14666666666668,111.6,147.14666666666668,105.81333333333333,297.6 +147.19611111111112,107.50277777777777,147.19611111111112,111.6375,147.19611111111112,105.8488888888889,297.7 +147.24555555555554,107.53888888888888,147.24555555555554,111.675,147.24555555555554,105.88444444444444,297.8 +147.295,107.57499999999999,147.295,111.71249999999999,147.295,105.92,297.90000000000003 +147.34444444444443,107.6111111111111,147.34444444444443,111.75,147.34444444444443,105.95555555555555,298.0 +147.39388888888888,107.64722222222221,147.39388888888888,111.7875,147.39388888888888,105.99111111111111,298.1 +147.44333333333333,107.68333333333332,147.44333333333333,111.825,147.44333333333333,106.02666666666667,298.2 +147.49277777777777,107.71944444444443,147.49277777777777,111.8625,147.49277777777777,106.06222222222222,298.3 +147.54222222222222,107.75555555555555,147.54222222222222,111.89999999999999,147.54222222222222,106.09777777777778,298.40000000000003 +147.59166666666667,107.79166666666666,147.59166666666667,111.9375,147.59166666666667,106.13333333333334,298.5 +147.64111111111112,107.82777777777777,147.64111111111112,111.975,147.64111111111112,106.16888888888889,298.6 +147.69055555555556,107.86388888888888,147.69055555555556,112.0125,147.69055555555556,106.20444444444445,298.7 +147.74,107.89999999999999,147.74,112.05,147.74,106.24,298.8 +147.78944444444446,107.9361111111111,147.78944444444446,112.08749999999999,147.78944444444446,106.27555555555556,298.90000000000003 +147.83888888888887,107.97222222222221,147.83888888888887,112.125,147.83888888888887,106.31111111111112,299.0 +147.88833333333332,108.00833333333333,147.88833333333332,112.1625,147.88833333333332,106.34666666666666,299.1 +147.93777777777777,108.04444444444444,147.93777777777777,112.2,147.93777777777777,106.38222222222223,299.2 +147.98722222222221,108.08055555555555,147.98722222222221,112.2375,147.98722222222221,106.41777777777777,299.3 +148.03666666666666,108.11666666666666,148.03666666666666,112.27499999999999,148.03666666666666,106.45333333333333,299.40000000000003 +148.0861111111111,108.15277777777777,148.0861111111111,112.3125,148.0861111111111,106.4888888888889,299.5 +148.13555555555556,108.18888888888888,148.13555555555556,112.35,148.13555555555556,106.52444444444444,299.6 +148.185,108.225,148.185,112.3875,148.185,106.56,299.7 +148.23444444444445,108.2611111111111,148.23444444444445,112.425,148.23444444444445,106.59555555555555,299.8 +148.2838888888889,108.29722222222222,148.2838888888889,112.46249999999999,148.2838888888889,106.63111111111111,299.90000000000003 +148.33333333333334,108.33333333333333,148.33333333333334,112.5,148.33333333333334,106.66666666666667,300.0 +148.38277777777776,108.36944444444444,148.38277777777776,112.5375,148.38277777777776,106.70222222222222,300.1 +148.4322222222222,108.40555555555555,148.4322222222222,112.575,148.4322222222222,106.73777777777778,300.2 +148.48166666666665,108.44166666666666,148.48166666666665,112.6125,148.48166666666665,106.77333333333333,300.3 +148.5311111111111,108.47777777777777,148.5311111111111,112.64999999999999,148.5311111111111,106.80888888888889,300.40000000000003 +148.58055555555555,108.51388888888889,148.58055555555555,112.6875,148.58055555555555,106.84444444444445,300.5 +148.63,108.54999999999998,148.63,112.725,148.63,106.88,300.6 +148.67944444444444,108.5861111111111,148.67944444444444,112.7625,148.67944444444444,106.91555555555556,300.7 +148.7288888888889,108.6222222222222,148.7288888888889,112.8,148.7288888888889,106.95111111111112,300.8 +148.77833333333334,108.65833333333332,148.77833333333334,112.83749999999999,148.77833333333334,106.98666666666666,300.90000000000003 +148.82777777777778,108.69444444444443,148.82777777777778,112.875,148.82777777777778,107.02222222222223,301.0 +148.87722222222223,108.73055555555554,148.87722222222223,112.9125,148.87722222222223,107.05777777777777,301.1 +148.92666666666668,108.76666666666665,148.92666666666668,112.95,148.92666666666668,107.09333333333333,301.2 +148.9761111111111,108.80277777777776,148.9761111111111,112.9875,148.9761111111111,107.1288888888889,301.3 +149.02555555555554,108.83888888888887,149.02555555555554,113.02499999999999,149.02555555555554,107.16444444444444,301.40000000000003 +149.075,108.87499999999999,149.075,113.0625,149.075,107.2,301.5 +149.12444444444444,108.9111111111111,149.12444444444444,113.1,149.12444444444444,107.23555555555555,301.6 +149.17388888888888,108.94722222222221,149.17388888888888,113.1375,149.17388888888888,107.27111111111111,301.7 +149.22333333333333,108.98333333333332,149.22333333333333,113.175,149.22333333333333,107.30666666666667,301.8 +149.27277777777778,109.01944444444443,149.27277777777778,113.21249999999999,149.27277777777778,107.34222222222222,301.90000000000003 +149.32222222222222,109.05555555555554,149.32222222222222,113.25,149.32222222222222,107.37777777777778,302.0 +149.37166666666667,109.09166666666665,149.37166666666667,113.2875,149.37166666666667,107.41333333333333,302.1 +149.42111111111112,109.12777777777777,149.42111111111112,113.325,149.42111111111112,107.44888888888889,302.2 +149.47055555555556,109.16388888888888,149.47055555555556,113.3625,149.47055555555556,107.48444444444445,302.3 +149.52,109.19999999999999,149.52,113.39999999999999,149.52,107.52,302.40000000000003 +149.56944444444443,109.2361111111111,149.56944444444443,113.4375,149.56944444444443,107.55555555555556,302.5 +149.61888888888888,109.27222222222221,149.61888888888888,113.475,149.61888888888888,107.5911111111111,302.6 +149.66833333333332,109.30833333333332,149.66833333333332,113.5125,149.66833333333332,107.62666666666667,302.7 +149.71777777777777,109.34444444444443,149.71777777777777,113.55,149.71777777777777,107.66222222222223,302.8 +149.76722222222222,109.38055555555555,149.76722222222222,113.58749999999999,149.76722222222222,107.69777777777777,302.90000000000003 +149.81666666666666,109.41666666666666,149.81666666666666,113.625,149.81666666666666,107.73333333333333,303.0 +149.8661111111111,109.45277777777777,149.8661111111111,113.6625,149.8661111111111,107.7688888888889,303.1 +149.91555555555556,109.48888888888888,149.91555555555556,113.7,149.91555555555556,107.80444444444444,303.2 +149.965,109.52499999999999,149.965,113.7375,149.965,107.84,303.3 +150.01444444444445,109.5611111111111,150.01444444444445,113.77499999999999,150.01444444444445,107.87555555555555,303.40000000000003 +150.0638888888889,109.59722222222221,150.0638888888889,113.8125,150.0638888888889,107.91111111111111,303.5 +150.11333333333334,109.63333333333333,150.11333333333334,113.85,150.11333333333334,107.94666666666667,303.6 +150.16277777777776,109.66944444444444,150.16277777777776,113.8875,150.16277777777776,107.98222222222222,303.7 +150.2122222222222,109.70555555555555,150.2122222222222,113.925,150.2122222222222,108.01777777777778,303.8 +150.26166666666666,109.74166666666666,150.26166666666666,113.96249999999999,150.26166666666666,108.05333333333333,303.90000000000003 +150.3111111111111,109.77777777777777,150.3111111111111,114.0,150.3111111111111,108.08888888888889,304.0 +150.36055555555555,109.81388888888888,150.36055555555555,114.0375,150.36055555555555,108.12444444444445,304.1 +150.41,109.85,150.41,114.075,150.41,108.16,304.2 +150.45944444444444,109.8861111111111,150.45944444444444,114.1125,150.45944444444444,108.19555555555556,304.3 +150.5088888888889,109.92222222222222,150.5088888888889,114.14999999999999,150.5088888888889,108.2311111111111,304.40000000000003 +150.55833333333334,109.95833333333333,150.55833333333334,114.1875,150.55833333333334,108.26666666666667,304.5 +150.60777777777778,109.99444444444444,150.60777777777778,114.225,150.60777777777778,108.30222222222223,304.6 +150.65722222222223,110.03055555555555,150.65722222222223,114.2625,150.65722222222223,108.33777777777777,304.7 +150.70666666666668,110.06666666666666,150.70666666666668,114.3,150.70666666666668,108.37333333333333,304.8 +150.7561111111111,110.10277777777777,150.7561111111111,114.33749999999999,150.7561111111111,108.40888888888888,304.90000000000003 +150.80555555555554,110.13888888888887,150.80555555555554,114.375,150.80555555555554,108.44444444444444,305.0 +150.855,110.17499999999998,150.855,114.4125,150.855,108.48,305.1 +150.90444444444444,110.2111111111111,150.90444444444444,114.45,150.90444444444444,108.51555555555555,305.2 +150.95388888888888,110.2472222222222,150.95388888888888,114.4875,150.95388888888888,108.55111111111111,305.3 +151.00333333333333,110.28333333333332,151.00333333333333,114.52499999999999,151.00333333333333,108.58666666666667,305.40000000000003 +151.05277777777778,110.31944444444443,151.05277777777778,114.5625,151.05277777777778,108.62222222222222,305.5 +151.10222222222222,110.35555555555554,151.10222222222222,114.6,151.10222222222222,108.65777777777778,305.6 +151.15166666666667,110.39166666666665,151.15166666666667,114.6375,151.15166666666667,108.69333333333333,305.7 +151.20111111111112,110.42777777777776,151.20111111111112,114.675,151.20111111111112,108.72888888888889,305.8 +151.25055555555556,110.46388888888887,151.25055555555556,114.71249999999999,151.25055555555556,108.76444444444445,305.90000000000003 +151.3,110.49999999999999,151.3,114.75,151.3,108.8,306.0 +151.34944444444443,110.5361111111111,151.34944444444443,114.7875,151.34944444444443,108.83555555555556,306.1 +151.39888888888888,110.57222222222221,151.39888888888888,114.825,151.39888888888888,108.8711111111111,306.2 +151.44833333333332,110.60833333333332,151.44833333333332,114.8625,151.44833333333332,108.90666666666667,306.3 +151.49777777777777,110.64444444444443,151.49777777777777,114.89999999999999,151.49777777777777,108.94222222222223,306.40000000000003 +151.54722222222222,110.68055555555554,151.54722222222222,114.9375,151.54722222222222,108.97777777777777,306.5 +151.59666666666666,110.71666666666665,151.59666666666666,114.975,151.59666666666666,109.01333333333334,306.6 +151.6461111111111,110.75277777777777,151.6461111111111,115.0125,151.6461111111111,109.04888888888888,306.7 +151.69555555555556,110.78888888888888,151.69555555555556,115.05,151.69555555555556,109.08444444444444,306.8 +151.745,110.82499999999999,151.745,115.08749999999999,151.745,109.12,306.90000000000003 +151.79444444444445,110.8611111111111,151.79444444444445,115.125,151.79444444444445,109.15555555555555,307.0 +151.8438888888889,110.89722222222221,151.8438888888889,115.1625,151.8438888888889,109.19111111111111,307.1 +151.89333333333332,110.93333333333332,151.89333333333332,115.19999999999999,151.89333333333332,109.22666666666666,307.20000000000005 +151.94277777777776,110.96944444444443,151.94277777777776,115.2375,151.94277777777776,109.26222222222222,307.3 +151.9922222222222,111.00555555555555,151.9922222222222,115.27499999999999,151.9922222222222,109.29777777777778,307.40000000000003 +152.04166666666666,111.04166666666666,152.04166666666666,115.3125,152.04166666666666,109.33333333333333,307.5 +152.0911111111111,111.07777777777777,152.0911111111111,115.35,152.0911111111111,109.36888888888889,307.6 +152.14055555555555,111.11388888888888,152.14055555555555,115.38749999999999,152.14055555555555,109.40444444444445,307.70000000000005 +152.19,111.14999999999999,152.19,115.425,152.19,109.44,307.8 +152.23944444444444,111.1861111111111,152.23944444444444,115.46249999999999,152.23944444444444,109.47555555555556,307.90000000000003 +152.2888888888889,111.22222222222221,152.2888888888889,115.5,152.2888888888889,109.5111111111111,308.0 +152.33833333333334,111.25833333333333,152.33833333333334,115.5375,152.33833333333334,109.54666666666667,308.1 +152.38777777777779,111.29444444444444,152.38777777777779,115.57499999999999,152.38777777777779,109.58222222222223,308.20000000000005 +152.43722222222223,111.33055555555555,152.43722222222223,115.6125,152.43722222222223,109.61777777777777,308.3 +152.48666666666665,111.36666666666666,152.48666666666665,115.64999999999999,152.48666666666665,109.65333333333334,308.40000000000003 +152.5361111111111,111.40277777777777,152.5361111111111,115.6875,152.5361111111111,109.68888888888888,308.5 +152.58555555555554,111.43888888888888,152.58555555555554,115.725,152.58555555555554,109.72444444444444,308.6 +152.635,111.475,152.635,115.76249999999999,152.635,109.76,308.70000000000005 +152.68444444444444,111.5111111111111,152.68444444444444,115.8,152.68444444444444,109.79555555555555,308.8 +152.73388888888888,111.54722222222222,152.73388888888888,115.83749999999999,152.73388888888888,109.83111111111111,308.90000000000003 +152.78333333333333,111.58333333333333,152.78333333333333,115.875,152.78333333333333,109.86666666666666,309.0 +152.83277777777778,111.61944444444444,152.83277777777778,115.9125,152.83277777777778,109.90222222222222,309.1 +152.88222222222223,111.65555555555555,152.88222222222223,115.94999999999999,152.88222222222223,109.93777777777778,309.20000000000005 +152.93166666666667,111.69166666666666,152.93166666666667,115.9875,152.93166666666667,109.97333333333333,309.3 +152.98111111111112,111.72777777777777,152.98111111111112,116.02499999999999,152.98111111111112,110.00888888888889,309.40000000000003 +153.03055555555557,111.76388888888887,153.03055555555557,116.0625,153.03055555555557,110.04444444444445,309.5 +153.07999999999998,111.79999999999998,153.07999999999998,116.1,153.07999999999998,110.08,309.6 +153.12944444444443,111.8361111111111,153.12944444444443,116.13749999999999,153.12944444444443,110.11555555555556,309.70000000000005 +153.17888888888888,111.8722222222222,153.17888888888888,116.175,153.17888888888888,110.1511111111111,309.8 +153.22833333333332,111.90833333333332,153.22833333333332,116.21249999999999,153.22833333333332,110.18666666666667,309.90000000000003 +153.27777777777777,111.94444444444443,153.27777777777777,116.25,153.27777777777777,110.22222222222223,310.0 +153.32722222222222,111.98055555555554,153.32722222222222,116.2875,153.32722222222222,110.25777777777778,310.1 +153.37666666666667,112.01666666666665,153.37666666666667,116.32499999999999,153.37666666666667,110.29333333333334,310.20000000000005 +153.4261111111111,112.05277777777776,153.4261111111111,116.3625,153.4261111111111,110.32888888888888,310.3 +153.47555555555556,112.08888888888887,153.47555555555556,116.39999999999999,153.47555555555556,110.36444444444444,310.40000000000003 +153.525,112.12499999999999,153.525,116.4375,153.525,110.4,310.5 +153.57444444444445,112.1611111111111,153.57444444444445,116.475,153.57444444444445,110.43555555555555,310.6 +153.6238888888889,112.19722222222221,153.6238888888889,116.51249999999999,153.6238888888889,110.47111111111111,310.70000000000005 +153.67333333333332,112.23333333333332,153.67333333333332,116.55,153.67333333333332,110.50666666666666,310.8 +153.72277777777776,112.26944444444443,153.72277777777776,116.58749999999999,153.72277777777776,110.54222222222222,310.90000000000003 +153.7722222222222,112.30555555555554,153.7722222222222,116.625,153.7722222222222,110.57777777777778,311.0 +153.82166666666666,112.34166666666665,153.82166666666666,116.6625,153.82166666666666,110.61333333333333,311.1 +153.8711111111111,112.37777777777777,153.8711111111111,116.69999999999999,153.8711111111111,110.64888888888889,311.20000000000005 +153.92055555555555,112.41388888888888,153.92055555555555,116.7375,153.92055555555555,110.68444444444444,311.3 +153.97,112.44999999999999,153.97,116.77499999999999,153.97,110.72,311.40000000000003 +154.01944444444445,112.4861111111111,154.01944444444445,116.8125,154.01944444444445,110.75555555555556,311.5 +154.0688888888889,112.52222222222221,154.0688888888889,116.85,154.0688888888889,110.7911111111111,311.6 +154.11833333333334,112.55833333333332,154.11833333333334,116.88749999999999,154.11833333333334,110.82666666666667,311.70000000000005 +154.1677777777778,112.59444444444443,154.1677777777778,116.925,154.1677777777778,110.86222222222223,311.8 +154.21722222222223,112.63055555555555,154.21722222222223,116.96249999999999,154.21722222222223,110.89777777777778,311.90000000000003 +154.26666666666665,112.66666666666666,154.26666666666665,117.0,154.26666666666665,110.93333333333334,312.0 +154.3161111111111,112.70277777777777,154.3161111111111,117.0375,154.3161111111111,110.96888888888888,312.1 +154.36555555555555,112.73888888888888,154.36555555555555,117.07499999999999,154.36555555555555,111.00444444444445,312.20000000000005 +154.415,112.77499999999999,154.415,117.1125,154.415,111.04,312.3 +154.46444444444444,112.8111111111111,154.46444444444444,117.14999999999999,154.46444444444444,111.07555555555555,312.40000000000003 +154.51388888888889,112.84722222222221,154.51388888888889,117.1875,154.51388888888889,111.11111111111111,312.5 +154.56333333333333,112.88333333333333,154.56333333333333,117.225,154.56333333333333,111.14666666666666,312.6 +154.61277777777778,112.91944444444444,154.61277777777778,117.26249999999999,154.61277777777778,111.18222222222222,312.70000000000005 +154.66222222222223,112.95555555555555,154.66222222222223,117.3,154.66222222222223,111.21777777777778,312.8 +154.71166666666667,112.99166666666666,154.71166666666667,117.33749999999999,154.71166666666667,111.25333333333333,312.90000000000003 +154.76111111111112,113.02777777777777,154.76111111111112,117.375,154.76111111111112,111.28888888888889,313.0 +154.81055555555557,113.06388888888888,154.81055555555557,117.4125,154.81055555555557,111.32444444444444,313.1 +154.85999999999999,113.1,154.85999999999999,117.44999999999999,154.85999999999999,111.36,313.20000000000005 +154.90944444444443,113.1361111111111,154.90944444444443,117.4875,154.90944444444443,111.39555555555556,313.3 +154.95888888888888,113.17222222222222,154.95888888888888,117.52499999999999,154.95888888888888,111.43111111111111,313.40000000000003 +155.00833333333333,113.20833333333333,155.00833333333333,117.5625,155.00833333333333,111.46666666666667,313.5 +155.05777777777777,113.24444444444444,155.05777777777777,117.6,155.05777777777777,111.50222222222222,313.6 +155.10722222222222,113.28055555555555,155.10722222222222,117.63749999999999,155.10722222222222,111.53777777777778,313.70000000000005 +155.15666666666667,113.31666666666666,155.15666666666667,117.675,155.15666666666667,111.57333333333334,313.8 +155.2061111111111,113.35277777777776,155.2061111111111,117.71249999999999,155.2061111111111,111.60888888888888,313.90000000000003 +155.25555555555556,113.38888888888887,155.25555555555556,117.75,155.25555555555556,111.64444444444445,314.0 +155.305,113.42499999999998,155.305,117.7875,155.305,111.68,314.1 +155.35444444444445,113.4611111111111,155.35444444444445,117.82499999999999,155.35444444444445,111.71555555555555,314.20000000000005 +155.4038888888889,113.4972222222222,155.4038888888889,117.8625,155.4038888888889,111.75111111111111,314.3 +155.45333333333332,113.53333333333332,155.45333333333332,117.89999999999999,155.45333333333332,111.78666666666666,314.40000000000003 +155.50277777777777,113.56944444444443,155.50277777777777,117.9375,155.50277777777777,111.82222222222222,314.5 +155.5522222222222,113.60555555555554,155.5522222222222,117.975,155.5522222222222,111.85777777777778,314.6 +155.60166666666666,113.64166666666665,155.60166666666666,118.01249999999999,155.60166666666666,111.89333333333333,314.70000000000005 +155.6511111111111,113.67777777777776,155.6511111111111,118.05,155.6511111111111,111.92888888888889,314.8 +155.70055555555555,113.71388888888887,155.70055555555555,118.08749999999999,155.70055555555555,111.96444444444444,314.90000000000003 +155.75,113.74999999999999,155.75,118.125,155.75,112.0,315.0 +155.79944444444445,113.7861111111111,155.79944444444445,118.1625,155.79944444444445,112.03555555555556,315.1 +155.8488888888889,113.82222222222221,155.8488888888889,118.19999999999999,155.8488888888889,112.07111111111111,315.20000000000005 +155.89833333333334,113.85833333333332,155.89833333333334,118.2375,155.89833333333334,112.10666666666667,315.3 +155.9477777777778,113.89444444444443,155.9477777777778,118.27499999999999,155.9477777777778,112.14222222222222,315.40000000000003 +155.9972222222222,113.93055555555554,155.9972222222222,118.3125,155.9972222222222,112.17777777777778,315.5 +156.04666666666665,113.96666666666665,156.04666666666665,118.35,156.04666666666665,112.21333333333334,315.6 +156.0961111111111,114.00277777777777,156.0961111111111,118.38749999999999,156.0961111111111,112.24888888888889,315.70000000000005 +156.14555555555555,114.03888888888888,156.14555555555555,118.425,156.14555555555555,112.28444444444445,315.8 +156.195,114.07499999999999,156.195,118.46249999999999,156.195,112.32,315.90000000000003 +156.24444444444444,114.1111111111111,156.24444444444444,118.5,156.24444444444444,112.35555555555555,316.0 +156.2938888888889,114.14722222222221,156.2938888888889,118.5375,156.2938888888889,112.39111111111112,316.1 +156.34333333333333,114.18333333333332,156.34333333333333,118.57499999999999,156.34333333333333,112.42666666666666,316.20000000000005 +156.39277777777778,114.21944444444443,156.39277777777778,118.6125,156.39277777777778,112.46222222222222,316.3 +156.44222222222223,114.25555555555555,156.44222222222223,118.64999999999999,156.44222222222223,112.49777777777778,316.40000000000003 +156.49166666666667,114.29166666666666,156.49166666666667,118.6875,156.49166666666667,112.53333333333333,316.5 +156.54111111111112,114.32777777777777,156.54111111111112,118.725,156.54111111111112,112.56888888888889,316.6 +156.59055555555554,114.36388888888888,156.59055555555554,118.76249999999999,156.59055555555554,112.60444444444444,316.70000000000005 +156.64,114.39999999999999,156.64,118.8,156.64,112.64,316.8 +156.68944444444443,114.4361111111111,156.68944444444443,118.83749999999999,156.68944444444443,112.67555555555556,316.90000000000003 +156.73888888888888,114.47222222222221,156.73888888888888,118.875,156.73888888888888,112.71111111111111,317.0 +156.78833333333333,114.50833333333333,156.78833333333333,118.9125,156.78833333333333,112.74666666666667,317.1 +156.83777777777777,114.54444444444444,156.83777777777777,118.94999999999999,156.83777777777777,112.78222222222222,317.20000000000005 +156.88722222222222,114.58055555555555,156.88722222222222,118.9875,156.88722222222222,112.81777777777778,317.3 +156.93666666666667,114.61666666666666,156.93666666666667,119.02499999999999,156.93666666666667,112.85333333333334,317.40000000000003 +156.98611111111111,114.65277777777777,156.98611111111111,119.0625,156.98611111111111,112.88888888888889,317.5 +157.03555555555556,114.68888888888888,157.03555555555556,119.1,157.03555555555556,112.92444444444445,317.6 +157.085,114.725,157.085,119.13749999999999,157.085,112.96,317.70000000000005 +157.13444444444445,114.7611111111111,157.13444444444445,119.175,157.13444444444445,112.99555555555555,317.8 +157.18388888888887,114.79722222222222,157.18388888888887,119.21249999999999,157.18388888888887,113.03111111111112,317.90000000000003 +157.23333333333332,114.83333333333333,157.23333333333332,119.25,157.23333333333332,113.06666666666666,318.0 +157.28277777777777,114.86944444444444,157.28277777777777,119.2875,157.28277777777777,113.10222222222222,318.1 +157.3322222222222,114.90555555555555,157.3322222222222,119.32499999999999,157.3322222222222,113.13777777777777,318.20000000000005 +157.38166666666666,114.94166666666666,157.38166666666666,119.3625,157.38166666666666,113.17333333333333,318.3 +157.4311111111111,114.97777777777776,157.4311111111111,119.39999999999999,157.4311111111111,113.2088888888889,318.40000000000003 +157.48055555555555,115.01388888888887,157.48055555555555,119.4375,157.48055555555555,113.24444444444444,318.5 +157.53,115.04999999999998,157.53,119.475,157.53,113.28,318.6 +157.57944444444445,115.0861111111111,157.57944444444445,119.51249999999999,157.57944444444445,113.31555555555556,318.70000000000005 +157.6288888888889,115.1222222222222,157.6288888888889,119.55,157.6288888888889,113.35111111111111,318.8 +157.67833333333334,115.15833333333332,157.67833333333334,119.58749999999999,157.67833333333334,113.38666666666667,318.90000000000003 +157.7277777777778,115.19444444444443,157.7277777777778,119.625,157.7277777777778,113.42222222222222,319.0 +157.7772222222222,115.23055555555554,157.7772222222222,119.6625,157.7772222222222,113.45777777777778,319.1 +157.82666666666665,115.26666666666665,157.82666666666665,119.69999999999999,157.82666666666665,113.49333333333334,319.20000000000005 +157.8761111111111,115.30277777777776,157.8761111111111,119.7375,157.8761111111111,113.52888888888889,319.3 +157.92555555555555,115.33888888888887,157.92555555555555,119.77499999999999,157.92555555555555,113.56444444444445,319.40000000000003 +157.975,115.37499999999999,157.975,119.8125,157.975,113.6,319.5 +158.02444444444444,115.4111111111111,158.02444444444444,119.85,158.02444444444444,113.63555555555556,319.6 +158.0738888888889,115.44722222222221,158.0738888888889,119.88749999999999,158.0738888888889,113.67111111111112,319.70000000000005 +158.12333333333333,115.48333333333332,158.12333333333333,119.925,158.12333333333333,113.70666666666666,319.8 +158.17277777777778,115.51944444444443,158.17277777777778,119.96249999999999,158.17277777777778,113.74222222222222,319.90000000000003 +158.22222222222223,115.55555555555554,158.22222222222223,120.0,158.22222222222223,113.77777777777777,320.0 +158.27166666666668,115.59166666666665,158.27166666666668,120.0375,158.27166666666668,113.81333333333333,320.1 +158.32111111111112,115.62777777777777,158.32111111111112,120.07499999999999,158.32111111111112,113.8488888888889,320.20000000000005 +158.37055555555554,115.66388888888888,158.37055555555554,120.1125,158.37055555555554,113.88444444444444,320.3 +158.42,115.69999999999999,158.42,120.14999999999999,158.42,113.92,320.40000000000003 +158.46944444444443,115.7361111111111,158.46944444444443,120.1875,158.46944444444443,113.95555555555555,320.5 +158.51888888888888,115.77222222222221,158.51888888888888,120.225,158.51888888888888,113.99111111111111,320.6 +158.56833333333333,115.80833333333332,158.56833333333333,120.26249999999999,158.56833333333333,114.02666666666667,320.70000000000005 +158.61777777777777,115.84444444444443,158.61777777777777,120.3,158.61777777777777,114.06222222222222,320.8 +158.66722222222222,115.88055555555555,158.66722222222222,120.33749999999999,158.66722222222222,114.09777777777778,320.90000000000003 +158.71666666666667,115.91666666666666,158.71666666666667,120.375,158.71666666666667,114.13333333333334,321.0 +158.76611111111112,115.95277777777777,158.76611111111112,120.4125,158.76611111111112,114.16888888888889,321.1 +158.81555555555556,115.98888888888888,158.81555555555556,120.44999999999999,158.81555555555556,114.20444444444445,321.20000000000005 +158.865,116.02499999999999,158.865,120.4875,158.865,114.24,321.3 +158.91444444444446,116.0611111111111,158.91444444444446,120.52499999999999,158.91444444444446,114.27555555555556,321.40000000000003 +158.96388888888887,116.09722222222221,158.96388888888887,120.5625,158.96388888888887,114.31111111111112,321.5 +159.01333333333332,116.13333333333333,159.01333333333332,120.6,159.01333333333332,114.34666666666666,321.6 +159.06277777777777,116.16944444444444,159.06277777777777,120.63749999999999,159.06277777777777,114.38222222222223,321.70000000000005 +159.11222222222221,116.20555555555555,159.11222222222221,120.675,159.11222222222221,114.41777777777777,321.8 +159.16166666666666,116.24166666666666,159.16166666666666,120.71249999999999,159.16166666666666,114.45333333333333,321.90000000000003 +159.2111111111111,116.27777777777777,159.2111111111111,120.75,159.2111111111111,114.4888888888889,322.0 +159.26055555555556,116.31388888888888,159.26055555555556,120.7875,159.26055555555556,114.52444444444444,322.1 +159.31,116.35,159.31,120.82499999999999,159.31,114.56,322.20000000000005 +159.35944444444445,116.3861111111111,159.35944444444445,120.8625,159.35944444444445,114.59555555555555,322.3 +159.4088888888889,116.42222222222222,159.4088888888889,120.89999999999999,159.4088888888889,114.63111111111111,322.40000000000003 +159.45833333333334,116.45833333333333,159.45833333333334,120.9375,159.45833333333334,114.66666666666667,322.5 +159.50777777777776,116.49444444444444,159.50777777777776,120.975,159.50777777777776,114.70222222222222,322.6 +159.5572222222222,116.53055555555555,159.5572222222222,121.01249999999999,159.5572222222222,114.73777777777778,322.70000000000005 +159.60666666666665,116.56666666666665,159.60666666666665,121.05,159.60666666666665,114.77333333333333,322.8 +159.6561111111111,116.60277777777776,159.6561111111111,121.08749999999999,159.6561111111111,114.80888888888889,322.90000000000003 +159.70555555555555,116.63888888888887,159.70555555555555,121.125,159.70555555555555,114.84444444444445,323.0 +159.755,116.67499999999998,159.755,121.1625,159.755,114.88,323.1 +159.80444444444444,116.7111111111111,159.80444444444444,121.19999999999999,159.80444444444444,114.91555555555556,323.20000000000005 +159.8538888888889,116.7472222222222,159.8538888888889,121.2375,159.8538888888889,114.95111111111112,323.3 +159.90333333333334,116.78333333333332,159.90333333333334,121.27499999999999,159.90333333333334,114.98666666666666,323.40000000000003 +159.95277777777778,116.81944444444443,159.95277777777778,121.3125,159.95277777777778,115.02222222222223,323.5 +160.00222222222223,116.85555555555554,160.00222222222223,121.35,160.00222222222223,115.05777777777777,323.6 +160.05166666666668,116.89166666666665,160.05166666666668,121.38749999999999,160.05166666666668,115.09333333333333,323.70000000000005 +160.1011111111111,116.92777777777776,160.1011111111111,121.425,160.1011111111111,115.1288888888889,323.8 +160.15055555555554,116.96388888888887,160.15055555555554,121.46249999999999,160.15055555555554,115.16444444444444,323.90000000000003 +160.2,116.99999999999999,160.2,121.5,160.2,115.2,324.0 +160.24944444444444,117.0361111111111,160.24944444444444,121.5375,160.24944444444444,115.23555555555555,324.1 +160.29888888888888,117.07222222222221,160.29888888888888,121.57499999999999,160.29888888888888,115.27111111111111,324.20000000000005 +160.34833333333333,117.10833333333332,160.34833333333333,121.6125,160.34833333333333,115.30666666666667,324.3 +160.39777777777778,117.14444444444443,160.39777777777778,121.64999999999999,160.39777777777778,115.34222222222222,324.40000000000003 +160.44722222222222,117.18055555555554,160.44722222222222,121.6875,160.44722222222222,115.37777777777778,324.5 +160.49666666666667,117.21666666666665,160.49666666666667,121.725,160.49666666666667,115.41333333333333,324.6 +160.54611111111112,117.25277777777777,160.54611111111112,121.76249999999999,160.54611111111112,115.44888888888889,324.70000000000005 +160.59555555555556,117.28888888888888,160.59555555555556,121.8,160.59555555555556,115.48444444444445,324.8 +160.645,117.32499999999999,160.645,121.83749999999999,160.645,115.52,324.90000000000003 +160.69444444444443,117.3611111111111,160.69444444444443,121.875,160.69444444444443,115.55555555555556,325.0 +160.74388888888888,117.39722222222221,160.74388888888888,121.9125,160.74388888888888,115.5911111111111,325.1 +160.79333333333332,117.43333333333332,160.79333333333332,121.94999999999999,160.79333333333332,115.62666666666667,325.20000000000005 +160.84277777777777,117.46944444444443,160.84277777777777,121.9875,160.84277777777777,115.66222222222223,325.3 +160.89222222222222,117.50555555555555,160.89222222222222,122.02499999999999,160.89222222222222,115.69777777777777,325.40000000000003 +160.94166666666666,117.54166666666666,160.94166666666666,122.0625,160.94166666666666,115.73333333333333,325.5 +160.9911111111111,117.57777777777777,160.9911111111111,122.1,160.9911111111111,115.7688888888889,325.6 +161.04055555555556,117.61388888888888,161.04055555555556,122.13749999999999,161.04055555555556,115.80444444444444,325.70000000000005 +161.09,117.64999999999999,161.09,122.175,161.09,115.84,325.8 +161.13944444444445,117.6861111111111,161.13944444444445,122.21249999999999,161.13944444444445,115.87555555555555,325.90000000000003 +161.1888888888889,117.72222222222221,161.1888888888889,122.25,161.1888888888889,115.91111111111111,326.0 +161.23833333333334,117.75833333333333,161.23833333333334,122.2875,161.23833333333334,115.94666666666667,326.1 +161.28777777777776,117.79444444444444,161.28777777777776,122.32499999999999,161.28777777777776,115.98222222222222,326.20000000000005 +161.3372222222222,117.83055555555555,161.3372222222222,122.3625,161.3372222222222,116.01777777777778,326.3 +161.38666666666666,117.86666666666666,161.38666666666666,122.39999999999999,161.38666666666666,116.05333333333333,326.40000000000003 +161.4361111111111,117.90277777777777,161.4361111111111,122.4375,161.4361111111111,116.08888888888889,326.5 +161.48555555555555,117.93888888888888,161.48555555555555,122.475,161.48555555555555,116.12444444444445,326.6 +161.535,117.975,161.535,122.51249999999999,161.535,116.16,326.70000000000005 +161.58444444444444,118.0111111111111,161.58444444444444,122.55,161.58444444444444,116.19555555555556,326.8 +161.6338888888889,118.04722222222222,161.6338888888889,122.58749999999999,161.6338888888889,116.2311111111111,326.90000000000003 +161.68333333333334,118.08333333333333,161.68333333333334,122.625,161.68333333333334,116.26666666666667,327.0 +161.73277777777778,118.11944444444444,161.73277777777778,122.6625,161.73277777777778,116.30222222222223,327.1 +161.78222222222223,118.15555555555555,161.78222222222223,122.69999999999999,161.78222222222223,116.33777777777777,327.20000000000005 +161.83166666666668,118.19166666666665,161.83166666666668,122.7375,161.83166666666668,116.37333333333333,327.3 +161.8811111111111,118.22777777777776,161.8811111111111,122.77499999999999,161.8811111111111,116.40888888888888,327.40000000000003 +161.93055555555554,118.26388888888887,161.93055555555554,122.8125,161.93055555555554,116.44444444444444,327.5 +161.98,118.29999999999998,161.98,122.85,161.98,116.48,327.6 +162.02944444444444,118.3361111111111,162.02944444444444,122.88749999999999,162.02944444444444,116.51555555555555,327.70000000000005 +162.07888888888888,118.3722222222222,162.07888888888888,122.925,162.07888888888888,116.55111111111111,327.8 +162.12833333333333,118.40833333333332,162.12833333333333,122.96249999999999,162.12833333333333,116.58666666666667,327.90000000000003 +162.17777777777778,118.44444444444443,162.17777777777778,123.0,162.17777777777778,116.62222222222222,328.0 +162.22722222222222,118.48055555555554,162.22722222222222,123.0375,162.22722222222222,116.65777777777778,328.1 +162.27666666666667,118.51666666666665,162.27666666666667,123.07499999999999,162.27666666666667,116.69333333333333,328.20000000000005 +162.32611111111112,118.55277777777776,162.32611111111112,123.1125,162.32611111111112,116.72888888888889,328.3 +162.37555555555556,118.58888888888887,162.37555555555556,123.14999999999999,162.37555555555556,116.76444444444445,328.40000000000003 +162.425,118.62499999999999,162.425,123.1875,162.425,116.8,328.5 +162.47444444444443,118.6611111111111,162.47444444444443,123.225,162.47444444444443,116.83555555555556,328.6 +162.52388888888888,118.69722222222221,162.52388888888888,123.26249999999999,162.52388888888888,116.8711111111111,328.70000000000005 +162.57333333333332,118.73333333333332,162.57333333333332,123.3,162.57333333333332,116.90666666666667,328.8 +162.62277777777777,118.76944444444443,162.62277777777777,123.33749999999999,162.62277777777777,116.94222222222223,328.90000000000003 +162.67222222222222,118.80555555555554,162.67222222222222,123.375,162.67222222222222,116.97777777777777,329.0 +162.72166666666666,118.84166666666665,162.72166666666666,123.4125,162.72166666666666,117.01333333333334,329.1 +162.7711111111111,118.87777777777777,162.7711111111111,123.44999999999999,162.7711111111111,117.04888888888888,329.20000000000005 +162.82055555555556,118.91388888888888,162.82055555555556,123.4875,162.82055555555556,117.08444444444444,329.3 +162.87,118.94999999999999,162.87,123.52499999999999,162.87,117.12,329.40000000000003 +162.91944444444445,118.9861111111111,162.91944444444445,123.5625,162.91944444444445,117.15555555555555,329.5 +162.9688888888889,119.02222222222221,162.9688888888889,123.6,162.9688888888889,117.19111111111111,329.6 +163.01833333333332,119.05833333333332,163.01833333333332,123.63749999999999,163.01833333333332,117.22666666666666,329.70000000000005 +163.06777777777776,119.09444444444443,163.06777777777776,123.675,163.06777777777776,117.26222222222222,329.8 +163.1172222222222,119.13055555555555,163.1172222222222,123.71249999999999,163.1172222222222,117.29777777777778,329.90000000000003 +163.16666666666666,119.16666666666666,163.16666666666666,123.75,163.16666666666666,117.33333333333333,330.0 +163.2161111111111,119.20277777777777,163.2161111111111,123.7875,163.2161111111111,117.36888888888889,330.1 +163.26555555555555,119.23888888888888,163.26555555555555,123.82499999999999,163.26555555555555,117.40444444444445,330.20000000000005 +163.315,119.27499999999999,163.315,123.8625,163.315,117.44,330.3 +163.36444444444444,119.3111111111111,163.36444444444444,123.89999999999999,163.36444444444444,117.47555555555556,330.40000000000003 +163.4138888888889,119.34722222222221,163.4138888888889,123.9375,163.4138888888889,117.5111111111111,330.5 +163.46333333333334,119.38333333333333,163.46333333333334,123.975,163.46333333333334,117.54666666666667,330.6 +163.51277777777779,119.41944444444444,163.51277777777779,124.01249999999999,163.51277777777779,117.58222222222223,330.70000000000005 +163.56222222222223,119.45555555555555,163.56222222222223,124.05,163.56222222222223,117.61777777777777,330.8 +163.61166666666665,119.49166666666666,163.61166666666665,124.08749999999999,163.61166666666665,117.65333333333334,330.90000000000003 +163.6611111111111,119.52777777777777,163.6611111111111,124.125,163.6611111111111,117.68888888888888,331.0 +163.71055555555554,119.56388888888888,163.71055555555554,124.1625,163.71055555555554,117.72444444444444,331.1 +163.76,119.6,163.76,124.19999999999999,163.76,117.76,331.20000000000005 +163.80944444444444,119.6361111111111,163.80944444444444,124.2375,163.80944444444444,117.79555555555555,331.3 +163.85888888888888,119.67222222222222,163.85888888888888,124.27499999999999,163.85888888888888,117.83111111111111,331.40000000000003 +163.90833333333333,119.70833333333333,163.90833333333333,124.3125,163.90833333333333,117.86666666666666,331.5 +163.95777777777778,119.74444444444444,163.95777777777778,124.35,163.95777777777778,117.90222222222222,331.6 +164.00722222222223,119.78055555555554,164.00722222222223,124.38749999999999,164.00722222222223,117.93777777777778,331.70000000000005 +164.05666666666667,119.81666666666665,164.05666666666667,124.425,164.05666666666667,117.97333333333333,331.8 +164.10611111111112,119.85277777777776,164.10611111111112,124.46249999999999,164.10611111111112,118.00888888888889,331.90000000000003 +164.15555555555557,119.88888888888887,164.15555555555557,124.5,164.15555555555557,118.04444444444445,332.0 +164.20499999999998,119.92499999999998,164.20499999999998,124.5375,164.20499999999998,118.08,332.1 +164.25444444444443,119.9611111111111,164.25444444444443,124.57499999999999,164.25444444444443,118.11555555555556,332.20000000000005 +164.30388888888888,119.9972222222222,164.30388888888888,124.6125,164.30388888888888,118.1511111111111,332.3 +164.35333333333332,120.03333333333332,164.35333333333332,124.64999999999999,164.35333333333332,118.18666666666667,332.40000000000003 +164.40277777777777,120.06944444444443,164.40277777777777,124.6875,164.40277777777777,118.22222222222223,332.5 +164.45222222222222,120.10555555555554,164.45222222222222,124.725,164.45222222222222,118.25777777777778,332.6 +164.50166666666667,120.14166666666665,164.50166666666667,124.76249999999999,164.50166666666667,118.29333333333334,332.70000000000005 +164.5511111111111,120.17777777777776,164.5511111111111,124.8,164.5511111111111,118.32888888888888,332.8 +164.60055555555556,120.21388888888887,164.60055555555556,124.83749999999999,164.60055555555556,118.36444444444444,332.90000000000003 +164.65,120.24999999999999,164.65,124.875,164.65,118.4,333.0 +164.69944444444445,120.2861111111111,164.69944444444445,124.9125,164.69944444444445,118.43555555555555,333.1 +164.7488888888889,120.32222222222221,164.7488888888889,124.94999999999999,164.7488888888889,118.47111111111111,333.20000000000005 +164.79833333333332,120.35833333333332,164.79833333333332,124.9875,164.79833333333332,118.50666666666666,333.3 +164.84777777777776,120.39444444444443,164.84777777777776,125.02499999999999,164.84777777777776,118.54222222222222,333.40000000000003 +164.8972222222222,120.43055555555554,164.8972222222222,125.0625,164.8972222222222,118.57777777777778,333.5 +164.94666666666666,120.46666666666665,164.94666666666666,125.1,164.94666666666666,118.61333333333333,333.6 +164.9961111111111,120.50277777777777,164.9961111111111,125.13749999999999,164.9961111111111,118.64888888888889,333.70000000000005 +165.04555555555555,120.53888888888888,165.04555555555555,125.175,165.04555555555555,118.68444444444444,333.8 +165.095,120.57499999999999,165.095,125.21249999999999,165.095,118.72,333.90000000000003 +165.14444444444445,120.6111111111111,165.14444444444445,125.25,165.14444444444445,118.75555555555556,334.0 +165.1938888888889,120.64722222222221,165.1938888888889,125.2875,165.1938888888889,118.7911111111111,334.1 +165.24333333333334,120.68333333333332,165.24333333333334,125.32499999999999,165.24333333333334,118.82666666666667,334.20000000000005 +165.2927777777778,120.71944444444443,165.2927777777778,125.3625,165.2927777777778,118.86222222222223,334.3 +165.34222222222223,120.75555555555555,165.34222222222223,125.39999999999999,165.34222222222223,118.89777777777778,334.40000000000003 +165.39166666666665,120.79166666666666,165.39166666666665,125.4375,165.39166666666665,118.93333333333334,334.5 +165.4411111111111,120.82777777777777,165.4411111111111,125.475,165.4411111111111,118.96888888888888,334.6 +165.49055555555555,120.86388888888888,165.49055555555555,125.51249999999999,165.49055555555555,119.00444444444445,334.70000000000005 +165.54,120.89999999999999,165.54,125.55,165.54,119.04,334.8 +165.58944444444444,120.9361111111111,165.58944444444444,125.58749999999999,165.58944444444444,119.07555555555555,334.90000000000003 +165.63888888888889,120.97222222222221,165.63888888888889,125.625,165.63888888888889,119.11111111111111,335.0 +165.68833333333333,121.00833333333333,165.68833333333333,125.6625,165.68833333333333,119.14666666666666,335.1 +165.73777777777778,121.04444444444444,165.73777777777778,125.69999999999999,165.73777777777778,119.18222222222222,335.20000000000005 +165.78722222222223,121.08055555555555,165.78722222222223,125.7375,165.78722222222223,119.21777777777778,335.3 +165.83666666666667,121.11666666666666,165.83666666666667,125.77499999999999,165.83666666666667,119.25333333333333,335.40000000000003 +165.88611111111112,121.15277777777777,165.88611111111112,125.8125,165.88611111111112,119.28888888888889,335.5 +165.93555555555557,121.18888888888888,165.93555555555557,125.85,165.93555555555557,119.32444444444444,335.6 +165.98499999999999,121.225,165.98499999999999,125.88749999999999,165.98499999999999,119.36,335.70000000000005 +166.03444444444443,121.2611111111111,166.03444444444443,125.925,166.03444444444443,119.39555555555556,335.8 +166.08388888888888,121.29722222222222,166.08388888888888,125.96249999999999,166.08388888888888,119.43111111111111,335.90000000000003 +166.13333333333333,121.33333333333333,166.13333333333333,126.0,166.13333333333333,119.46666666666667,336.0 +166.18277777777777,121.36944444444444,166.18277777777777,126.0375,166.18277777777777,119.50222222222222,336.1 +166.23222222222222,121.40555555555554,166.23222222222222,126.07499999999999,166.23222222222222,119.53777777777778,336.20000000000005 +166.28166666666667,121.44166666666665,166.28166666666667,126.1125,166.28166666666667,119.57333333333334,336.3 +166.3311111111111,121.47777777777776,166.3311111111111,126.14999999999999,166.3311111111111,119.60888888888888,336.40000000000003 +166.38055555555556,121.51388888888887,166.38055555555556,126.1875,166.38055555555556,119.64444444444445,336.5 +166.43,121.54999999999998,166.43,126.225,166.43,119.68,336.6 +166.47944444444445,121.5861111111111,166.47944444444445,126.26249999999999,166.47944444444445,119.71555555555555,336.70000000000005 +166.52888888888887,121.6222222222222,166.52888888888887,126.3,166.52888888888887,119.75111111111111,336.8 +166.57833333333332,121.65833333333332,166.57833333333332,126.33749999999999,166.57833333333332,119.78666666666666,336.90000000000003 +166.62777777777777,121.69444444444443,166.62777777777777,126.375,166.62777777777777,119.82222222222222,337.0 +166.6772222222222,121.73055555555554,166.6772222222222,126.4125,166.6772222222222,119.85777777777778,337.1 +166.72666666666666,121.76666666666665,166.72666666666666,126.44999999999999,166.72666666666666,119.89333333333333,337.20000000000005 +166.7761111111111,121.80277777777776,166.7761111111111,126.4875,166.7761111111111,119.92888888888889,337.3 +166.82555555555555,121.83888888888887,166.82555555555555,126.52499999999999,166.82555555555555,119.96444444444444,337.40000000000003 +166.875,121.87499999999999,166.875,126.5625,166.875,120.0,337.5 +166.92444444444445,121.9111111111111,166.92444444444445,126.6,166.92444444444445,120.03555555555556,337.6 +166.9738888888889,121.94722222222221,166.9738888888889,126.63749999999999,166.9738888888889,120.07111111111111,337.70000000000005 +167.02333333333334,121.98333333333332,167.02333333333334,126.675,167.02333333333334,120.10666666666667,337.8 +167.0727777777778,122.01944444444443,167.0727777777778,126.71249999999999,167.0727777777778,120.14222222222222,337.90000000000003 +167.1222222222222,122.05555555555554,167.1222222222222,126.75,167.1222222222222,120.17777777777778,338.0 +167.17166666666665,122.09166666666665,167.17166666666665,126.7875,167.17166666666665,120.21333333333334,338.1 +167.2211111111111,122.12777777777777,167.2211111111111,126.82499999999999,167.2211111111111,120.24888888888889,338.20000000000005 +167.27055555555555,122.16388888888888,167.27055555555555,126.8625,167.27055555555555,120.28444444444445,338.3 +167.32,122.19999999999999,167.32,126.89999999999999,167.32,120.32,338.40000000000003 +167.36944444444444,122.2361111111111,167.36944444444444,126.9375,167.36944444444444,120.35555555555555,338.5 +167.4188888888889,122.27222222222221,167.4188888888889,126.975,167.4188888888889,120.39111111111112,338.6 +167.46833333333333,122.30833333333332,167.46833333333333,127.01249999999999,167.46833333333333,120.42666666666666,338.70000000000005 +167.51777777777778,122.34444444444443,167.51777777777778,127.05,167.51777777777778,120.46222222222222,338.8 +167.56722222222223,122.38055555555555,167.56722222222223,127.08749999999999,167.56722222222223,120.49777777777778,338.90000000000003 +167.61666666666667,122.41666666666666,167.61666666666667,127.125,167.61666666666667,120.53333333333333,339.0 +167.66611111111112,122.45277777777777,167.66611111111112,127.1625,167.66611111111112,120.56888888888889,339.1 +167.71555555555554,122.48888888888888,167.71555555555554,127.19999999999999,167.71555555555554,120.60444444444444,339.20000000000005 +167.765,122.52499999999999,167.765,127.2375,167.765,120.64,339.3 +167.81444444444443,122.5611111111111,167.81444444444443,127.27499999999999,167.81444444444443,120.67555555555556,339.40000000000003 +167.86388888888888,122.59722222222221,167.86388888888888,127.3125,167.86388888888888,120.71111111111111,339.5 +167.91333333333333,122.63333333333333,167.91333333333333,127.35,167.91333333333333,120.74666666666667,339.6 +167.96277777777777,122.66944444444444,167.96277777777777,127.38749999999999,167.96277777777777,120.78222222222222,339.70000000000005 +168.01222222222222,122.70555555555555,168.01222222222222,127.425,168.01222222222222,120.81777777777778,339.8 +168.06166666666667,122.74166666666666,168.06166666666667,127.46249999999999,168.06166666666667,120.85333333333334,339.90000000000003 +168.11111111111111,122.77777777777777,168.11111111111111,127.5,168.11111111111111,120.88888888888889,340.0 +168.16055555555556,122.81388888888888,168.16055555555556,127.5375,168.16055555555556,120.92444444444445,340.1 +168.21,122.85,168.21,127.57499999999999,168.21,120.96,340.20000000000005 +168.25944444444445,122.8861111111111,168.25944444444445,127.6125,168.25944444444445,120.99555555555555,340.3 +168.30888888888887,122.92222222222222,168.30888888888887,127.64999999999999,168.30888888888887,121.03111111111112,340.40000000000003 +168.35833333333332,122.95833333333333,168.35833333333332,127.6875,168.35833333333332,121.06666666666666,340.5 +168.40777777777777,122.99444444444443,168.40777777777777,127.725,168.40777777777777,121.10222222222222,340.6 +168.4572222222222,123.03055555555554,168.4572222222222,127.76249999999999,168.4572222222222,121.13777777777777,340.70000000000005 +168.50666666666666,123.06666666666665,168.50666666666666,127.8,168.50666666666666,121.17333333333333,340.8 +168.5561111111111,123.10277777777776,168.5561111111111,127.83749999999999,168.5561111111111,121.2088888888889,340.90000000000003 +168.60555555555555,123.13888888888887,168.60555555555555,127.875,168.60555555555555,121.24444444444444,341.0 +168.655,123.17499999999998,168.655,127.9125,168.655,121.28,341.1 +168.70444444444445,123.2111111111111,168.70444444444445,127.94999999999999,168.70444444444445,121.31555555555556,341.20000000000005 +168.7538888888889,123.2472222222222,168.7538888888889,127.9875,168.7538888888889,121.35111111111111,341.3 +168.80333333333334,123.28333333333332,168.80333333333334,128.025,168.80333333333334,121.38666666666667,341.40000000000003 +168.8527777777778,123.31944444444443,168.8527777777778,128.0625,168.8527777777778,121.42222222222222,341.5 +168.9022222222222,123.35555555555554,168.9022222222222,128.1,168.9022222222222,121.45777777777778,341.6 +168.95166666666665,123.39166666666665,168.95166666666665,128.1375,168.95166666666665,121.49333333333334,341.70000000000005 +169.0011111111111,123.42777777777776,169.0011111111111,128.17499999999998,169.0011111111111,121.52888888888889,341.8 +169.05055555555555,123.46388888888887,169.05055555555555,128.2125,169.05055555555555,121.56444444444445,341.90000000000003 +169.1,123.49999999999999,169.1,128.25,169.1,121.6,342.0 +169.14944444444444,123.5361111111111,169.14944444444444,128.2875,169.14944444444444,121.63555555555556,342.1 +169.1988888888889,123.57222222222221,169.1988888888889,128.325,169.1988888888889,121.67111111111112,342.20000000000005 +169.24833333333333,123.60833333333332,169.24833333333333,128.36249999999998,169.24833333333333,121.70666666666666,342.3 +169.29777777777778,123.64444444444443,169.29777777777778,128.4,169.29777777777778,121.74222222222222,342.40000000000003 +169.34722222222223,123.68055555555554,169.34722222222223,128.4375,169.34722222222223,121.77777777777777,342.5 +169.39666666666668,123.71666666666665,169.39666666666668,128.475,169.39666666666668,121.81333333333333,342.6 +169.44611111111112,123.75277777777777,169.44611111111112,128.5125,169.44611111111112,121.8488888888889,342.70000000000005 +169.49555555555554,123.78888888888888,169.49555555555554,128.54999999999998,169.49555555555554,121.88444444444444,342.8 +169.545,123.82499999999999,169.545,128.5875,169.545,121.92,342.90000000000003 +169.59444444444443,123.8611111111111,169.59444444444443,128.625,169.59444444444443,121.95555555555555,343.0 +169.64388888888888,123.89722222222221,169.64388888888888,128.6625,169.64388888888888,121.99111111111111,343.1 +169.69333333333333,123.93333333333332,169.69333333333333,128.7,169.69333333333333,122.02666666666667,343.20000000000005 +169.74277777777777,123.96944444444443,169.74277777777777,128.73749999999998,169.74277777777777,122.06222222222222,343.3 +169.79222222222222,124.00555555555555,169.79222222222222,128.775,169.79222222222222,122.09777777777778,343.40000000000003 +169.84166666666667,124.04166666666666,169.84166666666667,128.8125,169.84166666666667,122.13333333333334,343.5 +169.89111111111112,124.07777777777777,169.89111111111112,128.85,169.89111111111112,122.16888888888889,343.6 +169.94055555555556,124.11388888888888,169.94055555555556,128.8875,169.94055555555556,122.20444444444445,343.70000000000005 +169.99,124.14999999999999,169.99,128.92499999999998,169.99,122.24,343.8 +170.03944444444443,124.1861111111111,170.03944444444443,128.9625,170.03944444444443,122.27555555555556,343.90000000000003 +170.08888888888887,124.22222222222221,170.08888888888887,129.0,170.08888888888887,122.31111111111112,344.0 +170.13833333333332,124.25833333333333,170.13833333333332,129.0375,170.13833333333332,122.34666666666666,344.1 +170.18777777777777,124.29444444444444,170.18777777777777,129.075,170.18777777777777,122.38222222222223,344.20000000000005 +170.23722222222221,124.33055555555555,170.23722222222221,129.11249999999998,170.23722222222221,122.41777777777777,344.3 +170.28666666666666,124.36666666666666,170.28666666666666,129.15,170.28666666666666,122.45333333333333,344.40000000000003 +170.3361111111111,124.40277777777777,170.3361111111111,129.1875,170.3361111111111,122.4888888888889,344.5 +170.38555555555556,124.43888888888888,170.38555555555556,129.225,170.38555555555556,122.52444444444444,344.6 +170.435,124.475,170.435,129.2625,170.435,122.56,344.70000000000005 +170.48444444444445,124.5111111111111,170.48444444444445,129.29999999999998,170.48444444444445,122.59555555555555,344.8 +170.5338888888889,124.54722222222222,170.5338888888889,129.3375,170.5338888888889,122.63111111111111,344.90000000000003 +170.58333333333334,124.58333333333333,170.58333333333334,129.375,170.58333333333334,122.66666666666667,345.0 +170.63277777777776,124.61944444444443,170.63277777777776,129.4125,170.63277777777776,122.70222222222222,345.1 +170.6822222222222,124.65555555555554,170.6822222222222,129.45,170.6822222222222,122.73777777777778,345.20000000000005 +170.73166666666665,124.69166666666665,170.73166666666665,129.48749999999998,170.73166666666665,122.77333333333333,345.3 +170.7811111111111,124.72777777777776,170.7811111111111,129.525,170.7811111111111,122.80888888888889,345.40000000000003 +170.83055555555555,124.76388888888887,170.83055555555555,129.5625,170.83055555555555,122.84444444444445,345.5 +170.88,124.79999999999998,170.88,129.6,170.88,122.88,345.6 +170.92944444444444,124.8361111111111,170.92944444444444,129.6375,170.92944444444444,122.91555555555556,345.70000000000005 +170.9788888888889,124.8722222222222,170.9788888888889,129.67499999999998,170.9788888888889,122.95111111111112,345.8 +171.02833333333334,124.90833333333332,171.02833333333334,129.7125,171.02833333333334,122.98666666666666,345.90000000000003 +171.07777777777778,124.94444444444443,171.07777777777778,129.75,171.07777777777778,123.02222222222223,346.0 +171.12722222222223,124.98055555555554,171.12722222222223,129.7875,171.12722222222223,123.05777777777777,346.1 +171.17666666666668,125.01666666666665,171.17666666666668,129.825,171.17666666666668,123.09333333333333,346.20000000000005 +171.2261111111111,125.05277777777776,171.2261111111111,129.86249999999998,171.2261111111111,123.1288888888889,346.3 +171.27555555555554,125.08888888888887,171.27555555555554,129.9,171.27555555555554,123.16444444444444,346.40000000000003 +171.325,125.12499999999999,171.325,129.9375,171.325,123.2,346.5 +171.37444444444444,125.1611111111111,171.37444444444444,129.975,171.37444444444444,123.23555555555555,346.6 +171.42388888888888,125.19722222222221,171.42388888888888,130.0125,171.42388888888888,123.27111111111111,346.70000000000005 +171.47333333333333,125.23333333333332,171.47333333333333,130.04999999999998,171.47333333333333,123.30666666666667,346.8 +171.52277777777778,125.26944444444443,171.52277777777778,130.0875,171.52277777777778,123.34222222222222,346.90000000000003 +171.57222222222222,125.30555555555554,171.57222222222222,130.125,171.57222222222222,123.37777777777778,347.0 +171.62166666666667,125.34166666666665,171.62166666666667,130.1625,171.62166666666667,123.41333333333333,347.1 +171.67111111111112,125.37777777777777,171.67111111111112,130.2,171.67111111111112,123.44888888888889,347.20000000000005 +171.72055555555556,125.41388888888888,171.72055555555556,130.23749999999998,171.72055555555556,123.48444444444445,347.3 +171.77,125.44999999999999,171.77,130.275,171.77,123.52,347.40000000000003 +171.81944444444443,125.4861111111111,171.81944444444443,130.3125,171.81944444444443,123.55555555555556,347.5 +171.86888888888888,125.52222222222221,171.86888888888888,130.35,171.86888888888888,123.5911111111111,347.6 +171.91833333333332,125.55833333333332,171.91833333333332,130.3875,171.91833333333332,123.62666666666667,347.70000000000005 +171.96777777777777,125.59444444444443,171.96777777777777,130.42499999999998,171.96777777777777,123.66222222222223,347.8 +172.01722222222222,125.63055555555555,172.01722222222222,130.4625,172.01722222222222,123.69777777777777,347.90000000000003 +172.06666666666666,125.66666666666666,172.06666666666666,130.5,172.06666666666666,123.73333333333333,348.0 +172.1161111111111,125.70277777777777,172.1161111111111,130.5375,172.1161111111111,123.7688888888889,348.1 +172.16555555555556,125.73888888888888,172.16555555555556,130.575,172.16555555555556,123.80444444444444,348.20000000000005 +172.215,125.77499999999999,172.215,130.61249999999998,172.215,123.84,348.3 +172.26444444444445,125.8111111111111,172.26444444444445,130.65,172.26444444444445,123.87555555555555,348.40000000000003 +172.3138888888889,125.84722222222221,172.3138888888889,130.6875,172.3138888888889,123.91111111111111,348.5 +172.36333333333334,125.88333333333333,172.36333333333334,130.725,172.36333333333334,123.94666666666667,348.6 +172.41277777777776,125.91944444444444,172.41277777777776,130.7625,172.41277777777776,123.98222222222222,348.70000000000005 +172.4622222222222,125.95555555555555,172.4622222222222,130.79999999999998,172.4622222222222,124.01777777777778,348.8 +172.51166666666666,125.99166666666666,172.51166666666666,130.8375,172.51166666666666,124.05333333333333,348.90000000000003 +172.5611111111111,126.02777777777777,172.5611111111111,130.875,172.5611111111111,124.08888888888889,349.0 +172.61055555555555,126.06388888888888,172.61055555555555,130.9125,172.61055555555555,124.12444444444445,349.1 +172.66,126.1,172.66,130.95,172.66,124.16,349.20000000000005 +172.70944444444444,126.1361111111111,172.70944444444444,130.98749999999998,172.70944444444444,124.19555555555556,349.3 +172.7588888888889,126.17222222222222,172.7588888888889,131.025,172.7588888888889,124.2311111111111,349.40000000000003 +172.80833333333334,126.20833333333331,172.80833333333334,131.0625,172.80833333333334,124.26666666666667,349.5 +172.85777777777778,126.24444444444443,172.85777777777778,131.1,172.85777777777778,124.30222222222223,349.6 +172.90722222222223,126.28055555555554,172.90722222222223,131.1375,172.90722222222223,124.33777777777777,349.70000000000005 +172.95666666666668,126.31666666666665,172.95666666666668,131.17499999999998,172.95666666666668,124.37333333333333,349.8 +173.0061111111111,126.35277777777776,173.0061111111111,131.2125,173.0061111111111,124.40888888888888,349.90000000000003 +173.05555555555554,126.38888888888887,173.05555555555554,131.25,173.05555555555554,124.44444444444444,350.0 +173.105,126.42499999999998,173.105,131.2875,173.105,124.48,350.1 +173.15444444444444,126.4611111111111,173.15444444444444,131.325,173.15444444444444,124.51555555555555,350.20000000000005 +173.20388888888888,126.4972222222222,173.20388888888888,131.36249999999998,173.20388888888888,124.55111111111111,350.3 +173.25333333333333,126.53333333333332,173.25333333333333,131.4,173.25333333333333,124.58666666666667,350.40000000000003 +173.30277777777778,126.56944444444443,173.30277777777778,131.4375,173.30277777777778,124.62222222222222,350.5 +173.35222222222222,126.60555555555554,173.35222222222222,131.475,173.35222222222222,124.65777777777778,350.6 +173.40166666666667,126.64166666666665,173.40166666666667,131.5125,173.40166666666667,124.69333333333333,350.70000000000005 +173.45111111111112,126.67777777777776,173.45111111111112,131.54999999999998,173.45111111111112,124.72888888888889,350.8 +173.50055555555556,126.71388888888887,173.50055555555556,131.5875,173.50055555555556,124.76444444444445,350.90000000000003 +173.55,126.74999999999999,173.55,131.625,173.55,124.8,351.0 +173.59944444444443,126.7861111111111,173.59944444444443,131.6625,173.59944444444443,124.83555555555556,351.1 +173.64888888888888,126.82222222222221,173.64888888888888,131.7,173.64888888888888,124.8711111111111,351.20000000000005 +173.69833333333332,126.85833333333332,173.69833333333332,131.73749999999998,173.69833333333332,124.90666666666667,351.3 +173.74777777777777,126.89444444444443,173.74777777777777,131.775,173.74777777777777,124.94222222222223,351.40000000000003 +173.79722222222222,126.93055555555554,173.79722222222222,131.8125,173.79722222222222,124.97777777777777,351.5 +173.84666666666666,126.96666666666665,173.84666666666666,131.85,173.84666666666666,125.01333333333334,351.6 +173.8961111111111,127.00277777777777,173.8961111111111,131.8875,173.8961111111111,125.04888888888888,351.70000000000005 +173.94555555555556,127.03888888888888,173.94555555555556,131.92499999999998,173.94555555555556,125.08444444444444,351.8 +173.995,127.07499999999999,173.995,131.9625,173.995,125.12,351.90000000000003 +174.04444444444445,127.1111111111111,174.04444444444445,132.0,174.04444444444445,125.15555555555555,352.0 +174.0938888888889,127.14722222222221,174.0938888888889,132.0375,174.0938888888889,125.19111111111111,352.1 +174.14333333333332,127.18333333333332,174.14333333333332,132.075,174.14333333333332,125.22666666666666,352.20000000000005 +174.19277777777776,127.21944444444443,174.19277777777776,132.11249999999998,174.19277777777776,125.26222222222222,352.3 +174.2422222222222,127.25555555555555,174.2422222222222,132.15,174.2422222222222,125.29777777777778,352.40000000000003 +174.29166666666666,127.29166666666666,174.29166666666666,132.1875,174.29166666666666,125.33333333333333,352.5 +174.3411111111111,127.32777777777777,174.3411111111111,132.225,174.3411111111111,125.36888888888889,352.6 +174.39055555555555,127.36388888888888,174.39055555555555,132.2625,174.39055555555555,125.40444444444445,352.70000000000005 +174.44,127.39999999999999,174.44,132.29999999999998,174.44,125.44,352.8 +174.48944444444444,127.4361111111111,174.48944444444444,132.3375,174.48944444444444,125.47555555555556,352.90000000000003 +174.5388888888889,127.47222222222221,174.5388888888889,132.375,174.5388888888889,125.5111111111111,353.0 +174.58833333333334,127.50833333333333,174.58833333333334,132.4125,174.58833333333334,125.54666666666667,353.1 +174.63777777777779,127.54444444444444,174.63777777777779,132.45,174.63777777777779,125.58222222222223,353.20000000000005 +174.68722222222223,127.58055555555555,174.68722222222223,132.48749999999998,174.68722222222223,125.61777777777777,353.3 +174.73666666666665,127.61666666666666,174.73666666666665,132.525,174.73666666666665,125.65333333333334,353.40000000000003 +174.7861111111111,127.65277777777777,174.7861111111111,132.5625,174.7861111111111,125.68888888888888,353.5 +174.83555555555554,127.68888888888888,174.83555555555554,132.6,174.83555555555554,125.72444444444444,353.6 +174.885,127.725,174.885,132.6375,174.885,125.76,353.70000000000005 +174.93444444444444,127.7611111111111,174.93444444444444,132.67499999999998,174.93444444444444,125.79555555555555,353.8 +174.98388888888888,127.79722222222222,174.98388888888888,132.7125,174.98388888888888,125.83111111111111,353.90000000000003 +175.03333333333333,127.83333333333331,175.03333333333333,132.75,175.03333333333333,125.86666666666666,354.0 +175.08277777777778,127.86944444444443,175.08277777777778,132.7875,175.08277777777778,125.90222222222222,354.1 +175.13222222222223,127.90555555555554,175.13222222222223,132.825,175.13222222222223,125.93777777777778,354.20000000000005 +175.18166666666667,127.94166666666665,175.18166666666667,132.86249999999998,175.18166666666667,125.97333333333333,354.3 +175.23111111111112,127.97777777777776,175.23111111111112,132.9,175.23111111111112,126.00888888888889,354.40000000000003 +175.28055555555557,128.01388888888889,175.28055555555557,132.9375,175.28055555555557,126.04444444444445,354.5 +175.32999999999998,128.04999999999998,175.32999999999998,132.975,175.32999999999998,126.08,354.6 +175.37944444444443,128.0861111111111,175.37944444444443,133.0125,175.37944444444443,126.11555555555556,354.70000000000005 +175.42888888888888,128.1222222222222,175.42888888888888,133.04999999999998,175.42888888888888,126.1511111111111,354.8 +175.47833333333332,128.15833333333333,175.47833333333332,133.0875,175.47833333333332,126.18666666666667,354.90000000000003 +175.52777777777777,128.19444444444443,175.52777777777777,133.125,175.52777777777777,126.22222222222223,355.0 +175.57722222222222,128.23055555555555,175.57722222222222,133.1625,175.57722222222222,126.25777777777778,355.1 +175.62666666666667,128.26666666666665,175.62666666666667,133.2,175.62666666666667,126.29333333333334,355.20000000000005 +175.6761111111111,128.30277777777778,175.6761111111111,133.23749999999998,175.6761111111111,126.32888888888888,355.3 +175.72555555555556,128.33888888888887,175.72555555555556,133.275,175.72555555555556,126.36444444444444,355.40000000000003 +175.775,128.375,175.775,133.3125,175.775,126.4,355.5 +175.82444444444445,128.4111111111111,175.82444444444445,133.35,175.82444444444445,126.43555555555555,355.6 +175.8738888888889,128.44722222222222,175.8738888888889,133.3875,175.8738888888889,126.47111111111111,355.70000000000005 +175.92333333333332,128.48333333333332,175.92333333333332,133.42499999999998,175.92333333333332,126.50666666666666,355.8 +175.97277777777776,128.51944444444445,175.97277777777776,133.4625,175.97277777777776,126.54222222222222,355.90000000000003 +176.0222222222222,128.55555555555554,176.0222222222222,133.5,176.0222222222222,126.57777777777778,356.0 +176.07166666666666,128.59166666666667,176.07166666666666,133.5375,176.07166666666666,126.61333333333333,356.1 +176.1211111111111,128.62777777777777,176.1211111111111,133.575,176.1211111111111,126.64888888888889,356.20000000000005 +176.17055555555555,128.66388888888886,176.17055555555555,133.61249999999998,176.17055555555555,126.68444444444444,356.3 +176.22,128.7,176.22,133.65,176.22,126.72,356.40000000000003 +176.26944444444445,128.7361111111111,176.26944444444445,133.6875,176.26944444444445,126.75555555555556,356.5 +176.3188888888889,128.7722222222222,176.3188888888889,133.725,176.3188888888889,126.7911111111111,356.6 +176.36833333333334,128.8083333333333,176.36833333333334,133.7625,176.36833333333334,126.82666666666667,356.70000000000005 +176.4177777777778,128.84444444444443,176.4177777777778,133.79999999999998,176.4177777777778,126.86222222222223,356.8 +176.46722222222223,128.88055555555553,176.46722222222223,133.8375,176.46722222222223,126.89777777777778,356.90000000000003 +176.51666666666665,128.91666666666666,176.51666666666665,133.875,176.51666666666665,126.93333333333334,357.0 +176.5661111111111,128.95277777777775,176.5661111111111,133.9125,176.5661111111111,126.96888888888888,357.1 +176.61555555555555,128.98888888888888,176.61555555555555,133.95,176.61555555555555,127.00444444444445,357.20000000000005 +176.665,129.02499999999998,176.665,133.98749999999998,176.665,127.04,357.3 +176.71444444444444,129.0611111111111,176.71444444444444,134.025,176.71444444444444,127.07555555555555,357.40000000000003 +176.76388888888889,129.0972222222222,176.76388888888889,134.0625,176.76388888888889,127.11111111111111,357.5 +176.81333333333333,129.13333333333333,176.81333333333333,134.1,176.81333333333333,127.14666666666666,357.6 +176.86277777777778,129.16944444444442,176.86277777777778,134.1375,176.86277777777778,127.18222222222222,357.70000000000005 +176.91222222222223,129.20555555555555,176.91222222222223,134.17499999999998,176.91222222222223,127.21777777777778,357.8 +176.96166666666667,129.24166666666665,176.96166666666667,134.2125,176.96166666666667,127.25333333333333,357.90000000000003 +177.01111111111112,129.27777777777777,177.01111111111112,134.25,177.01111111111112,127.28888888888889,358.0 +177.06055555555557,129.31388888888887,177.06055555555557,134.2875,177.06055555555557,127.32444444444444,358.1 +177.10999999999999,129.35,177.10999999999999,134.325,177.10999999999999,127.36,358.20000000000005 +177.15944444444443,129.3861111111111,177.15944444444443,134.36249999999998,177.15944444444443,127.39555555555556,358.3 +177.20888888888888,129.42222222222222,177.20888888888888,134.4,177.20888888888888,127.43111111111111,358.40000000000003 +177.25833333333333,129.45833333333331,177.25833333333333,134.4375,177.25833333333333,127.46666666666667,358.5 +177.30777777777777,129.49444444444444,177.30777777777777,134.475,177.30777777777777,127.50222222222222,358.6 +177.35722222222222,129.53055555555554,177.35722222222222,134.5125,177.35722222222222,127.53777777777778,358.70000000000005 +177.40666666666667,129.56666666666666,177.40666666666667,134.54999999999998,177.40666666666667,127.57333333333334,358.8 +177.4561111111111,129.60277777777776,177.4561111111111,134.5875,177.4561111111111,127.60888888888888,358.90000000000003 +177.50555555555556,129.63888888888889,177.50555555555556,134.625,177.50555555555556,127.64444444444445,359.0 +177.555,129.67499999999998,177.555,134.6625,177.555,127.68,359.1 +177.60444444444445,129.7111111111111,177.60444444444445,134.7,177.60444444444445,127.71555555555555,359.20000000000005 +177.65388888888887,129.7472222222222,177.65388888888887,134.73749999999998,177.65388888888887,127.75111111111111,359.3 +177.70333333333332,129.78333333333333,177.70333333333332,134.775,177.70333333333332,127.78666666666666,359.40000000000003 +177.75277777777777,129.81944444444443,177.75277777777777,134.8125,177.75277777777777,127.82222222222222,359.5 +177.8022222222222,129.85555555555555,177.8022222222222,134.85,177.8022222222222,127.85777777777778,359.6 +177.85166666666666,129.89166666666665,177.85166666666666,134.8875,177.85166666666666,127.89333333333333,359.70000000000005 +177.9011111111111,129.92777777777778,177.9011111111111,134.92499999999998,177.9011111111111,127.92888888888889,359.8 +177.95055555555555,129.96388888888887,177.95055555555555,134.9625,177.95055555555555,127.96444444444444,359.90000000000003 +178,130,178,135,178,128,360 diff --git a/rm_arm_control/data/robot_log.txt b/rm_arm_control/data/robot_log.txt new file mode 100644 index 0000000..ee1e16e --- /dev/null +++ b/rm_arm_control/data/robot_log.txt @@ -0,0 +1,29 @@ +[20240708 17:56:47] Begin API Testing. +[20240708 18:05:04] Begin API Testing. +[20240708 18:08:31] Begin API Testing. +[20240708 18:33:17] Begin API Testing. +[20240708 19:21:46] Begin API Testing. +[20240708 19:59:38] Begin API Testing. +[20240710 14:04:26] Begin API Testing. +[20240710 14:07:27] Begin API Testing. +[20240710 14:17:49] Begin API Testing. +[20240710 14:22:08] Begin API Testing. +[20240710 14:31:25] Begin API Testing. +[20240710 18:16:24] Begin API Testing. +[20240711 08:01:43] Begin API Testing. +[20240711 09:44:12] Begin API Testing. +[20240711 10:21:41] Begin API Testing. +[20240711 10:30:04] Begin API Testing. +[20240711 10:30:38] Begin API Testing. +[20240711 14:53:33] Begin API Testing. +[20240711 19:00:44] Begin API Testing. +[20240711 19:03:09] Begin API Testing. +[20240711 19:05:39] Begin API Testing. +[20240712 09:52:46] Begin API Testing. +[20240712 17:47:12] Begin API Testing. +[20240712 17:47:50] Begin API Testing. +[20240712 17:50:39] Begin API Testing. +[20240712 17:55:20] Begin API Testing. +[20240713 18:14:24] Begin API Testing. +[20240713 18:17:21] Begin API Testing. +[20240713 18:18:33] Begin API Testing. diff --git a/rm_arm_control/data/trajectory.txt b/rm_arm_control/data/trajectory.txt new file mode 100644 index 0000000..8fc80fe --- /dev/null +++ b/rm_arm_control/data/trajectory.txt @@ -0,0 +1,582 @@ +{"point":[-81,-16537,15047,-5480,-17,17705,-17]} +{"point":[-83,-16537,15048,-5484,-12,17707,-17]} +{"point":[-82,-16537,15054,-5480,-11,17703,-19]} +{"point":[-85,-16539,15059,-5483,-11,17699,-20]} +{"point":[-85,-16541,15063,-5484,-11,17690,-21]} +{"point":[-85,-16542,15069,-5486,-16,17663,-21]} +{"point":[-86,-16541,15076,-5484,-19,17649,-21]} +{"point":[-85,-16539,15080,-5486,-22,17633,-23]} +{"point":[-85,-16541,15091,-5487,-31,17608,-21]} +{"point":[-85,-16541,15096,-5487,-33,17564,-23]} +{"point":[-86,-16542,15099,-5487,-37,17543,-23]} +{"point":[-86,-16541,15109,-5491,-39,17523,-23]} +{"point":[-85,-16542,15111,-5493,-38,17490,-23]} +{"point":[-86,-16542,15114,-5495,-38,17473,-23]} +{"point":[-86,-16544,15118,-5500,-41,17457,-23]} +{"point":[-85,-16544,15118,-5502,-39,17438,-24]} +{"point":[-85,-16545,15118,-5504,-38,17394,-21]} +{"point":[-83,-16544,15118,-5511,-35,17368,-23]} +{"point":[-86,-16544,15118,-5516,-35,17337,-21]} +{"point":[-85,-16544,15120,-5520,-34,17284,-23]} +{"point":[-85,-16544,15118,-5520,-33,17259,-23]} +{"point":[-86,-16544,15117,-5523,-30,17233,-23]} +{"point":[-86,-16544,15117,-5523,-15,17173,-23]} +{"point":[-85,-16545,15115,-5523,-13,17135,-24]} +{"point":[-85,-16544,15110,-5522,-12,17094,-21]} +{"point":[-86,-16545,15103,-5522,-13,17056,-23]} +{"point":[-85,-16545,15096,-5523,-16,16987,-24]} +{"point":[-86,-16546,15087,-5524,-19,16954,-23]} +{"point":[-85,-16548,15071,-5526,-23,16914,-23]} +{"point":[-85,-16549,15060,-5526,-28,16846,-23]} +{"point":[-86,-16549,15040,-5526,-31,16807,-23]} +{"point":[-86,-16550,15028,-5528,-35,16770,-23]} +{"point":[-86,-16550,15019,-5530,-39,16728,-23]} +{"point":[-86,-16552,15011,-5530,-38,16636,-24]} +{"point":[-85,-16555,14995,-5530,-41,16593,-23]} +{"point":[-85,-16553,14988,-5534,-42,16556,-23]} +{"point":[-86,-16555,14978,-5534,-43,16476,-24]} +{"point":[-85,-16555,14953,-5537,-42,16435,-24]} +{"point":[-86,-16553,14945,-5537,-43,16397,-23]} +{"point":[-85,-16556,14929,-5539,-43,16316,-24]} +{"point":[-86,-16555,14911,-5538,-46,16278,-24]} +{"point":[-85,-16557,14870,-5541,-45,16232,-26]} +{"point":[-85,-16559,14849,-5544,-45,16141,-23]} +{"point":[-85,-16557,14824,-5542,-45,16090,-23]} +{"point":[-85,-16560,14779,-5544,-46,16044,-24]} +{"point":[-86,-16560,14761,-5544,-45,16004,-24]} +{"point":[-86,-16561,14751,-5545,-45,15911,-23]} +{"point":[-85,-16561,14731,-5545,-43,15862,-24]} +{"point":[-86,-16564,14724,-5546,-45,15802,-23]} +{"point":[-86,-16563,14723,-5549,-45,15695,-26]} +{"point":[-86,-16567,14714,-5549,-45,15632,-24]} +{"point":[-86,-16567,14712,-5548,-48,15558,-26]} +{"point":[-86,-16568,14710,-5549,-43,15435,-24]} +{"point":[-86,-16568,14709,-5548,-45,15358,-24]} +{"point":[-85,-16572,14710,-5549,-46,15286,-26]} +{"point":[-85,-16575,14710,-5550,-49,15126,-24]} +{"point":[-86,-16578,14710,-5553,-48,15044,-24]} +{"point":[-85,-16583,14710,-5556,-49,14960,-26]} +{"point":[-87,-16585,14710,-5560,-48,14861,-26]} +{"point":[-85,-16589,14712,-5564,-50,14702,-26]} +{"point":[-86,-16593,14712,-5567,-50,14615,-26]} +{"point":[-85,-16601,14710,-5575,-50,14507,-27]} +{"point":[-83,-16603,14712,-5579,-50,14422,-27]} +{"point":[-83,-16610,14712,-5587,-52,14224,-27]} +{"point":[-85,-16614,14712,-5593,-53,14143,-26]} +{"point":[-85,-16622,14710,-5612,-54,14041,-27]} +{"point":[-85,-16625,14709,-5623,-57,13840,-27]} +{"point":[-86,-16629,14710,-5637,-59,13730,-28]} +{"point":[-86,-16636,14710,-5664,-59,13614,-28]} +{"point":[-86,-16637,14710,-5679,-60,13476,-27]} +{"point":[-87,-16641,14710,-5704,-59,13241,-26]} +{"point":[-86,-16647,14709,-5754,-59,13094,-27]} +{"point":[-85,-16648,14709,-5776,-63,12977,-28]} +{"point":[-86,-16652,14710,-5799,-63,12696,-26]} +{"point":[-85,-16656,14712,-5824,-63,12578,-28]} +{"point":[-83,-16664,14712,-5880,-63,12436,-27]} +{"point":[-82,-16673,14712,-5905,-65,12201,-27]} +{"point":[-79,-16677,14710,-5936,-67,12076,-27]} +{"point":[-76,-16695,14713,-5995,-67,11962,-27]} +{"point":[-70,-16706,14712,-6024,-70,11846,-28]} +{"point":[-64,-16717,14710,-6050,-65,11587,-28]} +{"point":[-65,-16741,14710,-6113,-68,11458,-30]} +{"point":[-64,-16756,14710,-6149,-71,11344,-28]} +{"point":[-64,-16770,14712,-6183,-72,11061,-28]} +{"point":[-61,-16783,14710,-6212,-72,10931,-28]} +{"point":[-65,-16807,14712,-6274,-74,10811,-28]} +{"point":[-65,-16820,14713,-6310,-71,10509,-28]} +{"point":[-68,-16835,14713,-6344,-75,10372,-30]} +{"point":[-64,-16865,14712,-6411,-75,10251,-28]} +{"point":[-64,-16880,14710,-6454,-74,10092,-28]} +{"point":[-64,-16898,14712,-6490,-72,9806,-28]} +{"point":[-65,-16917,14712,-6534,-75,9684,-28]} +{"point":[-59,-16958,14710,-6619,-74,9559,-30]} +{"point":[-57,-16976,14709,-6660,-70,9283,-28]} +{"point":[-60,-16993,14710,-6705,-71,9137,-28]} +{"point":[-63,-17027,14710,-6803,-72,8985,-28]} +{"point":[-61,-17048,14712,-6852,-72,8834,-28]} +{"point":[-61,-17065,14710,-6906,-70,8544,-27]} +{"point":[-63,-17086,14709,-6965,-72,8412,-28]} +{"point":[-65,-17129,14709,-7087,-71,8243,-28]} +{"point":[-60,-17152,14710,-7154,-76,8098,-28]} +{"point":[-56,-17174,14710,-7224,-75,7845,-28]} +{"point":[-59,-17222,14713,-7355,-72,7700,-27]} +{"point":[-59,-17251,14712,-7425,-72,7454,-30]} +{"point":[-60,-17280,14712,-7498,-72,7323,-28]} +{"point":[-53,-17306,14712,-7570,-74,7196,-28]} +{"point":[-46,-17366,14712,-7727,-74,7073,-28]} +{"point":[-41,-17396,14712,-7807,-74,6796,-30]} +{"point":[-33,-17425,14713,-7882,-74,6796,-28]} +{"point":[-24,-17484,14712,-8042,-72,6514,-28]} +{"point":[-27,-17516,14712,-8118,-74,6370,-28]} +{"point":[-23,-17556,14713,-8191,-75,6076,-28]} +{"point":[-20,-17624,14713,-8260,-76,5929,-30]} +{"point":[-19,-17663,14712,-8410,-74,5802,-30]} +{"point":[-20,-17699,14712,-8492,-74,5533,-30]} +{"point":[-20,-17734,14713,-8581,-76,5399,-30]} +{"point":[-15,-17811,14713,-8747,-79,5265,-28]} +{"point":[-11,-17851,14714,-8828,-76,5144,-28]} +{"point":[-12,-17892,14713,-8911,-72,4912,-28]} +{"point":[-15,-17970,14712,-9085,-72,4753,-28]} +{"point":[-15,-18014,14712,-9168,-75,4615,-28]} +{"point":[-13,-18056,14710,-9245,-75,4356,-28]} +{"point":[-15,-18139,14709,-9404,-72,4224,-28]} +{"point":[-19,-18181,14710,-9497,-72,4093,-28]} +{"point":[-19,-18219,14712,-9580,-78,3838,-28]} +{"point":[-13,-18307,14714,-9688,-76,3696,-28]} +{"point":[-13,-18355,14712,-9884,-76,3582,-30]} +{"point":[-15,-18403,14713,-9976,-76,3477,-28]} +{"point":[-16,-18452,14714,-10059,-76,3230,-30]} +{"point":[-11,-18547,14716,-10259,-78,3118,-28]} +{"point":[-6,-18597,14714,-10356,-76,3006,-30]} +{"point":[-5,-18645,14716,-10445,-79,2808,-30]} +{"point":[-6,-18696,14716,-10535,-74,2702,-28]} +{"point":[-4,-18792,14713,-10732,-78,2579,-30]} +{"point":[-1,-18842,14713,-10825,-78,2447,-30]} +{"point":[-1,-18893,14714,-10924,-76,2231,-28]} +{"point":[-1,-18994,14713,-11112,-76,2121,-27]} +{"point":[1,-19046,14710,-11207,-71,2006,-30]} +{"point":[-1,-19097,14712,-11307,-72,1772,-30]} +{"point":[0,-19201,14713,-11515,-74,1685,-30]} +{"point":[0,-19246,14713,-11624,-72,1555,-30]} +{"point":[-4,-19293,14714,-11737,-78,1369,-28]} +{"point":[-4,-19400,14714,-11843,-75,1263,-28]} +{"point":[-5,-19452,14714,-12063,-74,1160,-30]} +{"point":[-4,-19506,14714,-12175,-76,976,-30]} +{"point":[1,-19620,14717,-12391,-76,885,-28]} +{"point":[2,-19675,14716,-12503,-78,808,-30]} +{"point":[5,-19731,14716,-12610,-76,638,-28]} +{"point":[5,-19793,14717,-12718,-78,554,-28]} +{"point":[5,-19910,14716,-12935,-75,472,-30]} +{"point":[5,-19966,14716,-13031,-78,293,-28]} +{"point":[5,-20026,14716,-13127,-74,210,-28]} +{"point":[5,-20147,14716,-13320,-74,123,-28]} +{"point":[4,-20208,14714,-13412,-74,42,-28]} +{"point":[8,-20264,14714,-13506,-75,-114,-30]} +{"point":[8,-20322,14714,-13610,-75,-184,-28]} +{"point":[5,-20433,14714,-13871,-71,-255,-28]} +{"point":[1,-20489,14716,-14011,-72,-414,-28]} +{"point":[2,-20547,14714,-14125,-71,-498,-30]} +{"point":[0,-20658,14713,-14338,-72,-565,-28]} +{"point":[-1,-20720,14713,-14442,-71,-644,-31]} +{"point":[0,-20779,14714,-14551,-70,-788,-28]} +{"point":[1,-20898,14716,-14772,-68,-852,-30]} +{"point":[5,-20961,14716,-14875,-68,-911,-30]} +{"point":[5,-21021,14717,-14979,-68,-1047,-30]} +{"point":[4,-21144,14717,-15091,-71,-1126,-28]} +{"point":[5,-21209,14717,-15309,-70,-1182,-30]} +{"point":[8,-21273,14719,-15419,-70,-1240,-28]} +{"point":[5,-21335,14717,-15527,-68,-1354,-30]} +{"point":[5,-21468,14714,-15751,-67,-1403,-27]} +{"point":[5,-21531,14716,-15868,-67,-1487,-30]} +{"point":[6,-21596,14717,-15989,-65,-1540,-30]} +{"point":[5,-21659,14714,-16116,-67,-1582,-28]} +{"point":[6,-21781,14719,-16351,-64,-1621,-28]} +{"point":[6,-21846,14719,-16472,-70,-1694,-28]} +{"point":[6,-21976,14716,-16588,-65,-1737,-30]} +{"point":[5,-22044,14717,-16817,-67,-1775,-30]} +{"point":[5,-22105,14719,-16934,-74,-1855,-28]} +{"point":[5,-22239,14719,-17135,-74,-1899,-30]} +{"point":[6,-22305,14719,-17252,-75,-1945,-28]} +{"point":[6,-22372,14717,-17357,-75,-2031,-30]} +{"point":[5,-22439,14716,-17462,-75,-2076,-30]} +{"point":[6,-22576,14716,-17682,-75,-2112,-30]} +{"point":[5,-22644,14716,-17791,-74,-2160,-28]} +{"point":[5,-22712,14716,-17899,-70,-2239,-30]} +{"point":[6,-22847,14717,-18135,-72,-2279,-28]} +{"point":[5,-22916,14717,-18246,-72,-2315,-28]} +{"point":[6,-22982,14716,-18347,-72,-2371,-28]} +{"point":[6,-23049,14717,-18444,-76,-2410,-28]} +{"point":[5,-23179,14717,-18674,-75,-2443,-30]} +{"point":[6,-23247,14717,-18800,-75,-2503,-30]} +{"point":[8,-23314,14717,-18923,-78,-2539,-30]} +{"point":[6,-23462,14719,-19160,-78,-2568,-28]} +{"point":[6,-23521,14720,-19278,-79,-2602,-30]} +{"point":[6,-23590,14721,-19388,-78,-2675,-30]} +{"point":[6,-23734,14720,-19606,-79,-2713,-30]} +{"point":[8,-23810,14719,-19712,-78,-2746,-30]} +{"point":[6,-23882,14721,-19819,-81,-2816,-28]} +{"point":[6,-24020,14719,-20033,-78,-2856,-30]} +{"point":[8,-24091,14719,-20139,-75,-2923,-30]} +{"point":[6,-24153,14720,-20254,-76,-2964,-30]} +{"point":[5,-24285,14719,-20367,-78,-2989,-30]} +{"point":[6,-24351,14716,-20591,-74,-3013,-30]} +{"point":[6,-24415,14714,-20705,-75,-3067,-28]} +{"point":[6,-24550,14716,-20815,-75,-3088,-28]} +{"point":[6,-24610,14717,-21034,-75,-3116,-28]} +{"point":[6,-24673,14720,-21143,-79,-3179,-30]} +{"point":[5,-24739,14720,-21248,-76,-3202,-28]} +{"point":[5,-24873,14720,-21467,-79,-3228,-30]} +{"point":[6,-24937,14719,-21564,-79,-3251,-30]} +{"point":[6,-25013,14717,-21669,-78,-3301,-30]} +{"point":[6,-25143,14720,-21884,-78,-3337,-30]} +{"point":[5,-25223,14723,-21983,-76,-3360,-30]} +{"point":[6,-25280,14728,-22085,-76,-3412,-28]} +{"point":[9,-25348,14735,-22181,-76,-3431,-28]} +{"point":[8,-25481,14730,-22377,-72,-3449,-28]} +{"point":[9,-25547,14723,-22478,-74,-3479,-28]} +{"point":[8,-25617,14720,-22572,-75,-3496,-28]} +{"point":[8,-25741,14717,-22788,-75,-3511,-27]} +{"point":[8,-25804,14719,-22909,-72,-3526,-30]} +{"point":[6,-25861,14721,-23026,-74,-3551,-30]} +{"point":[8,-25920,14719,-23135,-74,-3593,-30]} +{"point":[4,-26033,14717,-23329,-74,-3614,-28]} +{"point":[2,-26095,14717,-23421,-74,-3640,-30]} +{"point":[0,-26148,14717,-23512,-72,-3648,-28]} +{"point":[-2,-26268,14717,-23611,-72,-3651,-28]} +{"point":[-2,-26328,14717,-23789,-70,-3654,-28]} +{"point":[-1,-26385,14719,-23871,-68,-3654,-30]} +{"point":[0,-26438,14717,-23962,-68,-3655,-28]} +{"point":[1,-26555,14719,-24128,-65,-3655,-28]} +{"point":[4,-26619,14719,-24212,-68,-3655,-28]} +{"point":[4,-26666,14719,-24294,-63,-3657,-28]} +{"point":[5,-26775,14716,-24451,-60,-3655,-28]} +{"point":[5,-26828,14717,-24529,-61,-3657,-28]} +{"point":[6,-26890,14717,-24603,-57,-3655,-28]} +{"point":[6,-26986,14720,-24742,-59,-3657,-28]} +{"point":[6,-27036,14717,-24812,-54,-3655,-28]} +{"point":[6,-27082,14717,-24878,-54,-3657,-28]} +{"point":[5,-27129,14717,-24949,-53,-3655,-28]} +{"point":[0,-27218,14717,-25094,-56,-3655,-27]} +{"point":[0,-27262,14717,-25157,-54,-3657,-30]} +{"point":[1,-27305,14716,-25220,-54,-3655,-28]} +{"point":[-5,-27383,14714,-25349,-52,-3654,-28]} +{"point":[-5,-27426,14716,-25411,-52,-3655,-28]} +{"point":[-9,-27463,14716,-25471,-53,-3655,-28]} +{"point":[-9,-27494,14717,-25532,-53,-3657,-28]} +{"point":[-15,-27566,14716,-25638,-54,-3657,-30]} +{"point":[-20,-27592,14716,-25690,-53,-3655,-28]} +{"point":[-28,-27619,14716,-25742,-53,-3654,-28]} +{"point":[-31,-27670,14716,-25838,-50,-3657,-28]} +{"point":[-31,-27693,14716,-25881,-52,-3657,-28]} +{"point":[-34,-27714,14713,-25923,-49,-3654,-28]} +{"point":[-45,-27752,14714,-25990,-49,-3654,-28]} +{"point":[-56,-27773,14713,-26015,-48,-3655,-28]} +{"point":[-60,-27788,14714,-26039,-49,-3654,-28]} +{"point":[-71,-27810,14713,-26071,-46,-3654,-28]} +{"point":[-78,-27822,14712,-26084,-42,-3653,-28]} +{"point":[-85,-27828,14712,-26098,-46,-3653,-28]} +{"point":[-89,-27839,14710,-26107,-46,-3651,-28]} +{"point":[-89,-27842,14709,-26122,-43,-3651,-28]} +{"point":[-90,-27844,14708,-26125,-45,-3647,-27]} +{"point":[-90,-27844,14706,-26126,-43,-3646,-27]} +{"point":[-92,-27847,14703,-26125,-42,-3643,-28]} +{"point":[-93,-27844,14703,-26125,-41,-3633,-28]} +{"point":[-92,-27843,14702,-26122,-41,-3628,-28]} +{"point":[-93,-27840,14702,-26122,-39,-3621,-27]} +{"point":[-93,-27842,14702,-26120,-35,-3607,-28]} +{"point":[-93,-27839,14702,-26117,-26,-3574,-28]} +{"point":[-90,-27840,14703,-26115,-20,-3548,-28]} +{"point":[-87,-27838,14703,-26114,-9,-3511,-27]} +{"point":[-89,-27838,14703,-26113,-9,-3412,-27]} +{"point":[-90,-27839,14702,-26111,-6,-3352,-27]} +{"point":[-90,-27838,14702,-26106,-6,-3295,-28]} +{"point":[-93,-27838,14702,-26102,-5,-3175,-27]} +{"point":[-90,-27839,14703,-26096,-6,-3103,-28]} +{"point":[-92,-27838,14702,-26085,-8,-3033,-28]} +{"point":[-92,-27836,14701,-26074,-5,-2958,-27]} +{"point":[-92,-27838,14701,-26062,-8,-2789,-28]} +{"point":[-93,-27835,14701,-26037,-6,-2697,-27]} +{"point":[-92,-27835,14701,-26021,-8,-2500,-28]} +{"point":[-93,-27835,14702,-25997,-6,-2400,-28]} +{"point":[-92,-27836,14699,-25971,-8,-2308,-28]} +{"point":[-92,-27839,14701,-25901,-8,-2208,-30]} +{"point":[-92,-27836,14701,-25852,-6,-2007,-28]} +{"point":[-87,-27839,14703,-25771,-8,-1897,-27]} +{"point":[-86,-27839,14705,-25721,-8,-1771,-28]} +{"point":[-85,-27839,14705,-25666,-9,-1507,-27]} +{"point":[-86,-27838,14702,-25605,-8,-1355,-27]} +{"point":[-86,-27838,14703,-25499,-8,-1196,-27]} +{"point":[-87,-27836,14703,-25433,-16,-863,-27]} +{"point":[-86,-27836,14701,-25355,-17,-701,-28]} +{"point":[-87,-27835,14701,-25210,-19,-537,-28]} +{"point":[-89,-27833,14701,-25129,-22,-366,-28]} +{"point":[-90,-27833,14699,-25047,-27,-38,-27]} +{"point":[-93,-27831,14701,-24852,-24,112,-28]} +{"point":[-92,-27829,14699,-24754,-20,266,-28]} +{"point":[-92,-27829,14701,-24656,-27,646,-27]} +{"point":[-92,-27829,14699,-24548,-26,848,-27]} +{"point":[-93,-27829,14699,-24329,-26,1060,-28]} +{"point":[-92,-27829,14701,-24216,-28,1518,-28]} +{"point":[-90,-27828,14699,-24082,-35,1737,-28]} +{"point":[-92,-27828,14701,-23849,-34,1962,-28]} +{"point":[-90,-27827,14697,-23714,-34,2167,-28]} +{"point":[-90,-27827,14699,-23564,-37,2562,-27]} +{"point":[-89,-27825,14701,-23440,-37,2819,-27]} +{"point":[-82,-27827,14702,-23163,-39,3029,-28]} +{"point":[-79,-27827,14703,-22995,-42,3507,-27]} +{"point":[-78,-27827,14702,-22814,-38,3782,-28]} +{"point":[-74,-27829,14701,-22473,-42,4022,-28]} +{"point":[-78,-27825,14701,-22313,-37,4279,-27]} +{"point":[-78,-27824,14698,-22119,-38,4754,-26]} +{"point":[-78,-27810,14698,-21960,-42,4964,-27]} +{"point":[-75,-27806,14706,-21643,-43,5222,-28]} +{"point":[-74,-27802,14705,-21426,-45,5776,-27]} +{"point":[-71,-27789,14703,-21294,-48,6053,-26]} +{"point":[-74,-27784,14703,-20890,-48,6343,-26]} +{"point":[-72,-27776,14703,-20716,-43,6762,-27]} +{"point":[-75,-27770,14703,-20512,-48,6985,-24]} +{"point":[-71,-27750,14703,-20120,-41,7245,-26]} +{"point":[-67,-27735,14699,-19894,-38,7800,-26]} +{"point":[-70,-27715,14699,-19725,-38,8040,-26]} +{"point":[-70,-27685,14699,-19533,-39,8319,-26]} +{"point":[-71,-27664,14702,-19132,-41,8576,-24]} +{"point":[-75,-27638,14702,-18877,-41,9014,-26]} +{"point":[-85,-27592,14705,-18450,-43,9251,-26]} +{"point":[-86,-27568,14705,-18262,-38,9722,-26]} +{"point":[-87,-27537,14701,-18038,-34,9935,-24]} +{"point":[-92,-27496,14697,-17793,-27,10188,-26]} +{"point":[-92,-27438,14699,-17413,-22,10443,-24]} +{"point":[-93,-27393,14699,-17222,-24,10909,-24]} +{"point":[-92,-27354,14697,-17020,-27,11137,-24]} +{"point":[-89,-27261,14701,-16589,-28,11365,-24]} +{"point":[-90,-27215,14701,-16358,-37,11579,-26]} +{"point":[-90,-27165,14702,-16089,-30,11778,-24]} +{"point":[-92,-27121,14701,-15867,-19,12157,-24]} +{"point":[-90,-27022,14697,-15379,-6,12374,-24]} +{"point":[-92,-26974,14697,-15187,-9,12814,-24]} +{"point":[-92,-26913,14695,-14967,-8,13042,-24]} +{"point":[-85,-26801,14697,-14724,-13,13281,-24]} +{"point":[-81,-26738,14703,-14290,-24,13513,-24]} +{"point":[-82,-26674,14702,-14069,-41,13881,-26]} +{"point":[-82,-26545,14701,-13521,-42,14070,-26]} +{"point":[-85,-26478,14698,-13312,-35,14239,-24]} +{"point":[-87,-26411,14694,-13119,-35,14584,-24]} +{"point":[-90,-26334,14695,-12897,-37,14762,-24]} +{"point":[-90,-26185,14695,-12415,-35,14948,-24]} +{"point":[-90,-26107,14697,-12209,-42,15290,-26]} +{"point":[-89,-26032,14698,-11931,-43,15464,-24]} +{"point":[-86,-25876,14697,-11413,-48,15630,-26]} +{"point":[-86,-25809,14692,-11199,-37,15956,-23]} +{"point":[-89,-25725,14684,-10956,-33,16114,-24]} +{"point":[-93,-25555,14676,-10487,-35,16257,-24]} +{"point":[-92,-25449,14673,-10239,-35,16567,-23]} +{"point":[-92,-25353,14675,-10045,-41,16691,-23]} +{"point":[-89,-25176,14670,-9532,-45,16803,-26]} +{"point":[-87,-25066,14669,-9288,-53,16897,-24]} +{"point":[-83,-24967,14664,-9018,-53,17159,-24]} +{"point":[-83,-24867,14654,-8791,-52,17303,-26]} +{"point":[-90,-24661,14633,-8279,-48,17420,-26]} +{"point":[-92,-24570,14624,-8054,-52,17674,-26]} +{"point":[-85,-24456,14611,-7796,-53,17811,-24]} +{"point":[-82,-24242,14607,-7575,-57,17895,-24]} +{"point":[-79,-24132,14576,-7021,-64,17981,-26]} +{"point":[-74,-24027,14559,-6758,-64,18179,-26]} +{"point":[-74,-23796,14532,-6295,-60,18275,-26]} +{"point":[-79,-23678,14522,-6067,-61,18354,-26]} +{"point":[-87,-23553,14510,-5876,-64,18513,-27]} +{"point":[-89,-23431,14499,-5619,-67,18579,-24]} +{"point":[-89,-23181,14481,-5108,-65,18643,-26]} +{"point":[-83,-23054,14475,-4877,-64,18689,-26]} +{"point":[-78,-22934,14459,-4600,-64,18804,-24]} +{"point":[-76,-22679,14433,-4080,-63,18853,-26]} +{"point":[-78,-22550,14419,-3853,-68,18893,-26]} +{"point":[-82,-22413,14400,-3628,-65,18996,-26]} +{"point":[-86,-22270,14386,-3407,-65,19037,-24]} +{"point":[-86,-22016,14348,-2922,-67,19065,-26]} +{"point":[-83,-21876,14331,-2717,-65,19149,-26]} +{"point":[-79,-21737,14316,-2434,-71,19147,-26]} +{"point":[-79,-21457,14278,-1980,-67,19189,-27]} +{"point":[-79,-21312,14268,-1783,-64,19202,-26]} +{"point":[-85,-21163,14250,-1532,-68,19213,-24]} +{"point":[-86,-20875,14224,-1102,-61,19224,-26]} +{"point":[-81,-20732,14212,-898,-65,19220,-24]} +{"point":[-81,-20584,14195,-653,-61,19223,-23]} +{"point":[-82,-20435,14183,-435,-64,19215,-24]} +{"point":[-75,-20154,14151,79,-59,19217,-26]} +{"point":[-75,-19995,14139,292,-52,19227,-23]} +{"point":[-81,-19837,14135,479,-50,19206,-24]} +{"point":[-86,-19526,14092,922,-48,19208,-24]} +{"point":[-90,-19379,14081,1093,-46,19205,-24]} +{"point":[-92,-19197,14076,1325,-48,19193,-24]} +{"point":[-82,-18896,14044,1735,-46,19194,-24]} +{"point":[-83,-18737,14028,1995,-48,19161,-24]} +{"point":[-86,-18576,14014,2182,-39,19162,-24]} +{"point":[-89,-18255,13991,2428,-31,19164,-26]} +{"point":[-92,-18090,13966,2820,-30,19169,-26]} +{"point":[-90,-17926,13962,3019,-5,19091,-24]} +{"point":[-92,-17589,13923,3378,-2,19094,-26]} +{"point":[-90,-17421,13908,3610,-4,19065,-24]} +{"point":[-90,-17256,13901,3786,-2,19047,-24]} +{"point":[-86,-17093,13885,4025,-5,19031,-26]} +{"point":[-87,-16759,13852,4379,-8,19011,-26]} +{"point":[-90,-16596,13823,4578,-5,18995,-24]} +{"point":[-89,-16428,13801,4755,-6,18999,-24]} +{"point":[-90,-16085,13775,5105,-5,18988,-24]} +{"point":[-89,-15906,13750,5259,2,18925,-24]} +{"point":[-90,-15722,13726,5442,-16,18869,-23]} +{"point":[-89,-15556,13711,5623,-17,18833,-24]} +{"point":[-81,-15222,13675,5980,-15,18823,-26]} +{"point":[-82,-15044,13661,6151,-17,18801,-26]} +{"point":[-85,-14709,13645,6337,-15,18774,-24]} +{"point":[-89,-14523,13612,6645,-13,18794,-24]} +{"point":[-86,-14345,13603,6819,-15,18808,-26]} +{"point":[-83,-14169,13579,6992,0,18686,-26]} +{"point":[-83,-13800,13537,7310,-5,18660,-24]} +{"point":[-78,-13625,13517,7472,-4,18642,-24]} +{"point":[-71,-13441,13499,7603,-6,18650,-24]} +{"point":[-81,-13094,13485,7774,-13,18634,-26]} +{"point":[-86,-12919,13448,8101,-24,18594,-26]} +{"point":[-89,-12730,13432,8234,-39,18564,-24]} +{"point":[-90,-12356,13418,8491,-38,18518,-26]} +{"point":[-90,-12170,13411,8614,-35,18499,-26]} +{"point":[-90,-11986,13402,8774,-34,18444,-26]} +{"point":[-86,-11797,13384,8929,-31,18435,-24]} +{"point":[-87,-11420,13351,9159,-34,18425,-24]} +{"point":[-92,-11232,13327,9280,-33,18407,-26]} +{"point":[-92,-11050,13310,9409,-42,18378,-26]} +{"point":[-92,-10677,13274,9650,-41,18374,-26]} +{"point":[-92,-10491,13260,9788,-42,18363,-27]} +{"point":[-93,-10316,13245,9908,-39,18354,-26]} +{"point":[-90,-10133,13233,10059,-42,18338,-27]} +{"point":[-89,-9758,13198,10307,-41,18337,-26]} +{"point":[-89,-9573,13176,10430,-43,18325,-26]} +{"point":[-89,-9386,13160,10544,-50,18323,-26]} +{"point":[-90,-8996,13126,10765,-46,18321,-26]} +{"point":[-90,-8798,13108,10855,-49,18317,-27]} +{"point":[-90,-8609,13087,10965,-42,18315,-26]} +{"point":[-90,-8210,13046,11167,-37,18329,-27]} +{"point":[-90,-8007,13025,11258,-43,18322,-26]} +{"point":[-93,-7809,13001,11354,-39,18319,-27]} +{"point":[-93,-7621,12983,11443,-42,18323,-27]} +{"point":[-94,-7242,12952,11642,-38,18327,-26]} +{"point":[-93,-7045,12936,11741,-34,18343,-24]} +{"point":[-96,-6854,12921,11841,-37,18347,-26]} +{"point":[-93,-6455,12904,12025,-38,18351,-26]} +{"point":[-92,-6247,12888,12119,-42,18338,-27]} +{"point":[-92,-6048,12874,12223,-34,18333,-26]} +{"point":[-86,-5664,12843,12418,-28,18343,-26]} +{"point":[-81,-5454,12834,12503,-33,18337,-27]} +{"point":[-82,-5251,12811,12594,-30,18340,-26]} +{"point":[-83,-5051,12789,12683,-33,18344,-24]} +{"point":[-87,-4647,12752,12854,-30,18348,-26]} +{"point":[-86,-4437,12741,12933,-33,18344,-26]} +{"point":[-87,-4033,12727,13016,-30,18344,-24]} +{"point":[-87,-3839,12701,13179,-26,18351,-26]} +{"point":[-85,-3635,12682,13241,-13,18354,-26]} +{"point":[-85,-3438,12659,13300,-9,18358,-26]} +{"point":[-87,-3029,12612,13440,-17,18358,-26]} +{"point":[-86,-2808,12594,13521,-35,18355,-26]} +{"point":[-86,-2595,12582,13605,-34,18354,-27]} +{"point":[-81,-2194,12573,13774,-33,18352,-27]} +{"point":[-67,-1994,12569,13851,-30,18354,-26]} +{"point":[-53,-1789,12556,13930,-35,18344,-27]} +{"point":[-54,-1380,12535,14105,-34,18352,-26]} +{"point":[-72,-1170,12525,14177,-35,18354,-26]} +{"point":[-85,-947,12514,14245,-49,18347,-27]} +{"point":[-85,-736,12490,14308,-50,18344,-27]} +{"point":[-92,-331,12472,14447,-52,18349,-27]} +{"point":[-93,-129,12468,14517,-48,18349,-27]} +{"point":[-92,75,12459,14587,-46,18352,-27]} +{"point":[-97,486,12437,14720,-49,18356,-27]} +{"point":[-96,692,12431,14783,-52,18356,-27]} +{"point":[-93,903,12424,14848,-56,18349,-27]} +{"point":[-93,1308,12396,14977,-53,18349,-27]} +{"point":[-93,1507,12381,15032,-48,18355,-26]} +{"point":[-94,1707,12365,15087,-52,18348,-26]} +{"point":[-96,1903,12344,15143,-52,18354,-26]} +{"point":[-96,2308,12307,15250,-50,18355,-27]} +{"point":[-90,2511,12295,15302,-50,18355,-27]} +{"point":[-92,2719,12281,15350,-54,18349,-26]} +{"point":[-81,3117,12249,15448,-52,18348,-27]} +{"point":[-76,3312,12238,15488,-46,18354,-27]} +{"point":[-72,3506,12231,15523,-50,18351,-28]} +{"point":[-72,3701,12219,15560,-43,18355,-27]} +{"point":[-71,4103,12150,15640,-46,18356,-28]} +{"point":[-64,4302,12109,15676,-52,18355,-28]} +{"point":[-74,4704,12089,15702,-54,18352,-28]} +{"point":[-76,4891,12053,15766,-54,18348,-28]} +{"point":[-74,5079,12038,15794,-53,18349,-27]} +{"point":[-74,5266,12025,15814,-48,18351,-27]} +{"point":[-93,5640,11980,15861,-46,18356,-27]} +{"point":[-97,5837,11964,15873,-53,18356,-27]} +{"point":[-97,6027,11947,15887,-52,18359,-27]} +{"point":[-96,6411,11918,15902,-57,18354,-27]} +{"point":[-94,6594,11896,15913,-50,18354,-27]} +{"point":[-93,6770,11877,15921,-50,18354,-27]} +{"point":[-94,7124,11857,15923,-54,18347,-28]} +{"point":[-96,7293,11804,15943,-52,18354,-27]} +{"point":[-96,7470,11781,15950,-50,18354,-27]} +{"point":[-94,7654,11760,15957,-50,18352,-27]} +{"point":[-87,8036,11708,15967,-50,18354,-27]} +{"point":[-87,8190,11682,15972,-56,18341,-27]} +{"point":[-86,8359,11656,15981,-52,18347,-27]} +{"point":[-85,8690,11601,15987,-52,18347,-27]} +{"point":[-89,8867,11578,15990,-53,18344,-27]} +{"point":[-94,9004,11546,16000,-46,18356,-27]} +{"point":[-97,9332,11501,16005,-49,18354,-27]} +{"point":[-97,9515,11482,16014,-52,18354,-27]} +{"point":[-94,9659,11464,16018,-53,18354,-27]} +{"point":[-83,9852,11447,16022,-52,18348,-27]} +{"point":[-81,10145,11416,16023,-48,18348,-28]} +{"point":[-82,10316,11395,16022,-52,18347,-27]} +{"point":[-85,10601,11355,16024,-49,18349,-28]} +{"point":[-86,10769,11324,16029,-45,18351,-26]} +{"point":[-83,10899,11288,16031,-48,18355,-27]} +{"point":[-85,11204,11233,16030,-49,18354,-26]} +{"point":[-83,11351,11206,16030,-52,18354,-28]} +{"point":[-71,11504,11180,16030,-53,18352,-27]} +{"point":[-38,11802,11144,16023,-54,18345,-27]} +{"point":[-34,11955,11131,16027,-49,18347,-27]} +{"point":[-37,12071,11126,16027,-48,18349,-27]} +{"point":[-43,12208,11122,16027,-43,18351,-28]} +{"point":[-60,12488,11049,16035,-43,18354,-27]} +{"point":[-67,12602,11030,16035,-49,18356,-26]} +{"point":[-78,12730,11016,16037,-49,18355,-28]} +{"point":[-74,12999,10976,16034,-50,18355,-27]} +{"point":[-60,13125,10958,16031,-52,18354,-27]} +{"point":[-41,13249,10942,16034,-52,18354,-27]} +{"point":[-33,13509,10927,16027,-54,18347,-27]} +{"point":[-37,13642,10921,16020,-53,18345,-27]} +{"point":[-42,13742,10904,16022,-52,18347,-28]} +{"point":[-46,13962,10840,16023,-50,18348,-27]} +{"point":[-43,14068,10780,16026,-46,18352,-27]} +{"point":[-43,14177,10739,16024,-52,18352,-27]} +{"point":[-50,14282,10713,16022,-50,18352,-28]} +{"point":[-43,14488,10666,16024,-50,18352,-27]} +{"point":[-34,14589,10647,16024,-52,18351,-28]} +{"point":[-28,14705,10632,16026,-49,18351,-28]} +{"point":[-30,14886,10606,16024,-50,18349,-28]} +{"point":[-37,14989,10589,16022,-49,18351,-27]} +{"point":[-39,15076,10566,16020,-54,18345,-27]} +{"point":[-39,15174,10530,16015,-54,18344,-27]} +{"point":[-54,15352,10465,16016,-53,18347,-27]} +{"point":[-64,15431,10439,16016,-52,18347,-28]} +{"point":[-71,15511,10413,16018,-52,18347,-27]} +{"point":[-81,15667,10342,16018,-49,18348,-27]} +{"point":[-81,15735,10314,16020,-49,18349,-27]} +{"point":[-85,15795,10283,16022,-50,18351,-27]} +{"point":[-90,15934,10226,16020,-52,18349,-27]} +{"point":[-94,15998,10202,16020,-52,18349,-28]} +{"point":[-97,16059,10174,16018,-53,18349,-28]} +{"point":[-98,16119,10150,16018,-54,18349,-28]} +{"point":[-98,16243,10103,16018,-54,18348,-28]} +{"point":[-98,16288,10075,16019,-56,18349,-28]} +{"point":[-98,16336,10047,16018,-54,18349,-26]} +{"point":[-96,16436,9983,16018,-54,18348,-28]} +{"point":[-96,16483,9953,16018,-53,18348,-28]} +{"point":[-94,16535,9923,16018,-52,18348,-27]} +{"point":[-87,16607,9886,16019,-53,18348,-28]} +{"point":[-83,16645,9819,16019,-52,18348,-27]} +{"point":[-78,16678,9784,16019,-49,18348,-27]} +{"point":[-76,16708,9757,16020,-50,18349,-28]} +{"point":[-75,16758,9710,16020,-48,18349,-28]} +{"point":[-75,16780,9687,16022,-49,18352,-27]} +{"point":[-76,16807,9663,16022,-48,18351,-27]} +{"point":[-71,16828,9643,16022,-49,18349,-27]} +{"point":[-67,16866,9598,16019,-48,18349,-27]} +{"point":[-61,16883,9577,16016,-48,18347,-27]} +{"point":[-60,16912,9547,16018,-46,18347,-27]} +{"point":[-56,16921,9521,16016,-43,18347,-28]} +{"point":[-48,16927,9482,16018,-33,18348,-28]} +{"point":[-39,16931,9431,16020,-37,18349,-27]} +{"point":[-39,16935,9393,16018,-37,18349,-27]} +{"point":[-37,16936,9312,16020,-38,18351,-27]} +{"point":[-34,16936,9286,16020,-45,18349,-27]} +{"point":[-28,16935,9272,16020,-42,18349,-27]} +{"point":[-26,16935,9262,16020,-41,18349,-27]} +{"point":[-22,16932,9251,16019,-37,18349,-27]} +{"point":[-20,16935,9232,16019,-19,18348,-27]} +{"point":[-15,16931,9177,16019,-13,18347,-27]} +{"point":[-15,16927,9137,16018,-16,18348,-26]} +{"point":[-12,16925,9103,16018,-22,18348,-28]} diff --git a/rm_arm_control/driver/arm_driver.cpp b/rm_arm_control/driver/arm_driver.cpp new file mode 100644 index 0000000..c537537 --- /dev/null +++ b/rm_arm_control/driver/arm_driver.cpp @@ -0,0 +1,79 @@ +#include "arm_driver.hpp" +#include + +ArmStatusCallbackData ArmDriverDefault::leftCallbackData_; +ArmStatusCallbackData ArmDriverDefault::rightCallbackData_; +std::shared_mutex ArmDriverDefault::default_update_status_mutex_; +ArmDriverDefault::ArmStatusCallbackFun ArmDriverDefault::armStatusCallback_ = nullptr; + +ArmDriverDefault::ArmDriverDefault() +{ + armStatusCallback_ = nullptr; + armMoveFun_ = nullptr; + initFlag_ = ARM_MOVE_STATUS_UNINIT; +} + +ArmDriverDefault::~ArmDriverDefault() +{ +} + +void ArmDriverDefault::PublicThreadUpdate() +{ + std::unique_lock lock(default_update_status_mutex_); + armStatusCallback_(&leftCallbackData_); + armStatusCallback_(&rightCallbackData_); +} + +int ArmDriverDefault::DefaultArmMove(const float points[USED_ARM_DOF], int armId) +{ + ArmStatusCallbackData *callbackData; + if (armId == LEFT_ARM) { + callbackData = &leftCallbackData_; + } else if (armId == RIGHT_ARM) { + callbackData = &rightCallbackData_; + } else { + return UNKNOWN_ERR; + } + std::shared_lock lock(default_update_status_mutex_); + callbackData->errCode = 0; + for (size_t i = 0; i < USED_ARM_DOF; i++) { + callbackData->jointAngle[i] = points[i]; + } + armStatusCallback_(callbackData); + return 0; +} + +int ArmDriverDefault::Init() +{ + if (armStatusCallback_ == nullptr) { + return UNKNOWN_ERR; + } + if (armMoveFun_ == nullptr) { + armMoveFun_ = DefaultArmMove; + memset(&leftCallbackData_, 0, sizeof(ArmStatusCallbackData)); + memset(&rightCallbackData_, 0, sizeof(ArmStatusCallbackData)); + rightCallbackData_.armId = RIGHT_ARM; + leftCallbackData_.armId = LEFT_ARM; + for (size_t i = 0; i < USED_ARM_DOF; i++) { + leftCallbackData_.jointEnFlag[i] = true; + rightCallbackData_.jointEnFlag[i] = true; + leftCallbackData_.jointTemp[i] = 0.0f; + rightCallbackData_.jointTemp[i] = 0.0f; + leftCallbackData_.jointVoltage[i] = 0.0f; + rightCallbackData_.jointVoltage[i] = 0.0f; + leftCallbackData_.jointCurrent[i] = 0.0f; + rightCallbackData_.jointCurrent[i] = 0.0f; + leftCallbackData_.jointSpeed[i] = 0.0f; + rightCallbackData_.jointSpeed[i] = 0.0f; + leftCallbackData_.jointTorque[i] = 0.0f; + rightCallbackData_.jointTorque[i] = 0.0f; + leftCallbackData_.jointErrCode[i] = 0; + rightCallbackData_.jointErrCode[i] = 0; + leftCallbackData_.jointAngle[i] = 0.0f; + rightCallbackData_.jointAngle[i] = 0.0f; + } + } + initFlag_ = ARM_MOVE_STATUS_READY; + return OK; +} + diff --git a/rm_arm_control/driver/rm_arm_driver.cpp b/rm_arm_control/driver/rm_arm_driver.cpp new file mode 100644 index 0000000..bd9a92d --- /dev/null +++ b/rm_arm_control/driver/rm_arm_driver.cpp @@ -0,0 +1,167 @@ +#include "arm_driver.hpp" +#include "rm_arm_driver.hpp" +#include + +RmArmDriver::RmArmDriver() +{ + rmService_ = nullptr; + initFlag_ = RM_DRIVER_UNINIT; +} + +RmArmDriver::~RmArmDriver() +{ + if (rmService_ != nullptr) { + rmService_->rm_destroy(); + delete rmService_; + } +} + +RmArmDriver::RmArmStatusCallbackFun RmArmDriver::armStatusCallback_ = nullptr; +RmArmDriver::ApiLogFunc RmArmDriver::customApiLog_ = nullptr; +rm_robot_handle *RmArmDriver::leftRobotHandle_; +rm_robot_handle *RmArmDriver::rightRobotHandle_; +RM_Service *RmArmDriver::rmService_ = nullptr; + +int RmArmDriver::ArmMove(const float points[USED_ARM_DOF], int armId) +{ + float joints[ARM_DOF] = {0}; + for (size_t i = 0; i < USED_ARM_DOF; i++) { + joints[i] = points[i]; + } + if (armId == LEFT_ARM) { + int result = rmService_->rm_movej_canfd(leftRobotHandle_, joints, true, 0); + if (result != 0) { + api_log("Error moving left arm to joint space!"); + return UNKNOWN_ERR; + } + } else if (armId == RIGHT_ARM) { + int result = rmService_->rm_movej_canfd(rightRobotHandle_, joints, true, 0); + if (result != 0) { + api_log("Error moving right arm to joint space!"); + return UNKNOWN_ERR; + } + } else { + api_log("Invalid armId: %d", armId); + return UNKNOWN_ERR; + } + return OK; +} + +void RmArmDriver::CallbackRmRealtimeArmJointState(rm_realtime_arm_joint_state_t data) +{ + ArmStatusCallbackData callbackData; + callbackData.errCode = 0; + if (armStatusCallback_ == nullptr) { + return; + } + if (strcmp(data.arm_ip, LEFT_ARM_IP_ADDRESS) == 0) { + callbackData.armId = LEFT_ARM; + } + else if (strcmp(data.arm_ip, RIGHT_ARM_IP_ADDRESS) == 0) { + callbackData.armId = RIGHT_ARM; + } else { + api_log("Unknown arm ip: %s", data.arm_ip); + return; + } + + callbackData.errCode = data.errCode; + for (size_t i = 0; i < USED_ARM_DOF; i++) { + callbackData.jointCurrent[i] = data.joint_status.joint_current[i]; + callbackData.jointEnFlag[i] = data.joint_status.joint_en_flag[i]; + callbackData.jointAngle[i] = data.joint_status.joint_position[i]; + callbackData.jointSpeed[i] = data.joint_status.joint_speed[i]; + callbackData.jointTemp[i] = data.joint_status.joint_temperature[i]; + callbackData.jointVoltage[i] = data.joint_status.joint_voltage[i]; + callbackData.jointTorque[i] = data.force_sensor.force[i]; + callbackData.jointErrCode[i] = data.joint_status.joint_err_code[i]; + } + + armStatusCallback_(&callbackData); +} + +void RmArmDriver::api_log(const char* format, ...) +{ + va_list args; + va_start(args, format);// 初始化可变参数列表 + customApiLog_(format, args);// 调用函数指针,传递 va_list + va_end(args);// 清理可变参数列表 +} + +int RmArmDriver::InitHandle(rm_robot_handle **robotHandle_, const char *robot_ip_address, int robot_port, rm_realtime_push_config_t *config) +{ + *robotHandle_ = rmService_->rm_create_robot_arm(robot_ip_address, robot_port); + if (*robotHandle_ == NULL) { + api_log("Failed to create arm(%s) handle.", robot_ip_address); + return UNKNOWN_ERR; + } + if ((*robotHandle_)->id <= 0) { + api_log("Failed to create arm(%s) handle. %d", robot_ip_address, (*robotHandle_)->id); + return UNKNOWN_ERR; + } + + int result = rmService_-> rm_set_realtime_push(*robotHandle_, *config); + if (result != 0) { + api_log("Failed to set realtime push for arm(%s).", robot_ip_address); + return UNKNOWN_ERR; + } + result = rm_set_arm_max_line_speed(*robotHandle_, 0.01f); + if (result != 0) { + api_log("Failed to set max line speed for arm(%s).", robot_ip_address); + return UNKNOWN_ERR; + } + + rm_robot_info_t robot_info; + int info_result = rmService_->rm_get_robot_info(*robotHandle_, &robot_info); + if (info_result != 0) { + api_log("Failed to get robot info(%s)", robot_ip_address); + return UNKNOWN_ERR; + } + int dof = robot_info.arm_dof; + if (dof != USED_ARM_DOF) { + api_log("Invalid degree of freedom(%s)", robot_ip_address); + return UNKNOWN_ERR; + } + return 0; +} + +int RmArmDriver::Init() +{ + if (initFlag_ == RM_DRIVER_INIT_OK) { + return OK; + } + if (customApiLog_ == nullptr || armStatusCallback_ == nullptr) { + return UNKNOWN_ERR; + } + rmService_ = new RM_Service(); + if (rmService_ == nullptr) { + return UNKNOWN_ERR; + } + int result = rmService_->rm_init(RM_TRIPLE_MODE_E); + if (result != 0) { + rmService_->rm_destroy(); + delete rmService_; + return UNKNOWN_ERR; + } + + rmService_->rm_set_log_call_back(customApiLog_, 3); + rmService_->rm_realtime_arm_state_call_back(CallbackRmRealtimeArmJointState); + + int robot_port = ARM_IP_PORT; + rm_realtime_push_config_t config = {20, true, 8089, 0, "192.168.2.3"}; + result = InitHandle(&leftRobotHandle_, LEFT_ARM_IP_ADDRESS, robot_port, &config); + if (result != 0) { + rmService_->rm_destroy(); + delete rmService_; + return UNKNOWN_ERR; + } + config = {20, true, 8089, 0, "192.168.2.19"}; + result = InitHandle(&rightRobotHandle_, RIGHT_ARM_IP_ADDRESS, robot_port, &config); + if (result != 0) { + rmService_->rm_destroy(); + delete rmService_; + return UNKNOWN_ERR; + } + + initFlag_ = RM_DRIVER_INIT_OK; + return OK; +} \ No newline at end of file diff --git a/rm_arm_control/include/arm_driver.hpp b/rm_arm_control/include/arm_driver.hpp new file mode 100644 index 0000000..f8876e8 --- /dev/null +++ b/rm_arm_control/include/arm_driver.hpp @@ -0,0 +1,75 @@ +#ifndef ARM_DRIVER_HPP +#define ARM_DRIVER_HPP + +#include +#include +#include +#include "arm_define.h" +#include +#include + + +struct ArmStatusCallbackData { + int errCode; ///< 数据解析错误码,-3为数据解析错误,代表推送的数据不完整或格式不正确 + int armId; ///< 机械臂ID,0为左臂,1为右臂 + float jointCurrent[USED_ARM_DOF]; ///< 关节电流,单位mA,精度:0.001mA + bool jointEnFlag[USED_ARM_DOF]; ///< 当前关节使能状态 ,1为上使能,0为掉使能 + float jointAngle[USED_ARM_DOF]; ///< 关节角度,单位度,精度:0.001度 + float jointSpeed[USED_ARM_DOF]; ///< 关节速度,单位度/秒,精度:0.001度/秒 + float jointTemp[USED_ARM_DOF]; ///< 关节温度,单位摄氏度,精度:0.1摄氏度 + float jointVoltage[USED_ARM_DOF]; ///< 关节电压,单位V,精度:0.01V + float jointTorque[USED_ARM_DOF]; ///< 关节力矩,单位Nm,精度:0.001Nm + int jointErrCode[USED_ARM_DOF]; ///< 当前关节错误码 +}; + +enum ArmDriverStatus { + ARM_MOVE_STATUS_UNINIT = 0, + ARM_MOVE_STATUS_READY = 1, + ARM_MOVE_STATUS_ERROR = 2 +}; + +class ArmDriverDefault +{ +public: + ArmDriverDefault(); + ~ArmDriverDefault(); + + int Init(); + + using ArmStatusCallbackFun = void(*)(ArmStatusCallbackData *data); + void RegArmStatusCallback(ArmStatusCallbackFun callback) { + armStatusCallback_ = callback; + } + static void CallArmStatusCallback(ArmStatusCallbackData *data) { + if (armStatusCallback_ != nullptr) { + armStatusCallback_(data); + } + } + + using ArmMoveFun = int(*)(const float points[USED_ARM_DOF], int armId); + void RegArmMoveCallback(ArmMoveFun callback) { + armMoveFun_ = callback; + } + + int ArmMove(const float points[USED_ARM_DOF], int armId) { + if (armMoveFun_ != nullptr) { + return armMoveFun_(points, armId); + } + return UNKNOWN_ERR; + } + + void PublicThreadUpdate(); + +private: + int initFlag_; + + static ArmStatusCallbackFun armStatusCallback_; + ArmMoveFun armMoveFun_; + + static std::shared_mutex default_update_status_mutex_; + static ArmStatusCallbackData leftCallbackData_; + static ArmStatusCallbackData rightCallbackData_; + static int DefaultArmMove(const float points[USED_ARM_DOF], int armId); +}; + +#endif // ARM_DRIVER_HPP \ No newline at end of file diff --git a/rm_arm_control/include/arm_driver_define.hpp b/rm_arm_control/include/arm_driver_define.hpp new file mode 100644 index 0000000..bb3ae83 --- /dev/null +++ b/rm_arm_control/include/arm_driver_define.hpp @@ -0,0 +1,30 @@ +#ifndef ARM_DRIVER_DEFINE_HPP +#define ARM_DRIVER_DEFINE_HPP + +#include "rm_arm_driver.hpp" +#include "rm_driver_kinematics.hpp" +#include "trajectory.hpp" + +int InitRmDriver2(RmArmDriverAndKinematics **armDriver, RmArmDriverAndKinematics **armKinematics); +int InitSimulatorDriver(ArmDriverDefault **armDriver, TrapezoidalTrajectoryKinematics **armKinematics); +int InitRmArmDriver(ArmDriverDefault **armDriver, TrapezoidalTrajectoryKinematics **armKinematics); + +#ifdef REAL_ROBOT +using ArmDriver = RmArmDriverAndKinematics; + +using KinematicsManager = TrajectoryManager; +using Trajectory = NodataTrajectory; +using Kinematics = RmArmDriverAndKinematics; + +#define ArmInitFunc InitRmDriver2 +#else +using ArmDriver = ArmDriverDefault; + +using KinematicsManager = TrajectoryManager; +using Trajectory = TrapezoidalTrajectory; +using Kinematics = TrapezoidalTrajectoryKinematics; + +#define ArmInitFunc InitSimulatorDriver +#endif + +#endif // ARM_DRIVER_DEFINE_HPP \ No newline at end of file diff --git a/rm_arm_control/include/goal_manager.hpp b/rm_arm_control/include/goal_manager.hpp new file mode 100644 index 0000000..26304c7 --- /dev/null +++ b/rm_arm_control/include/goal_manager.hpp @@ -0,0 +1,39 @@ +#ifndef GOAL_MANAGER_HPP +#define GOAL_MANAGER_HPP + +#include +#include +#include "arm_define.h" + +class GoalManager +{ +public: + GoalManager(); + ~GoalManager(); + + int AddGoal(const float points[GOAL_DATA_LENGTH], const int64_t &index, int type); + int ConsumeGoal(); + int RemoveGoal(int64_t index); + int SetNowGoalResult(int result); + int GetNowGoalResult() const; + int GetGoalType() const; + int64_t GetGoalNowIndex(); + int64_t GetCompeletedGoalNowIndex(); + void ClearGoals(); + const float* GetGoal() const; + void GoalRunOff(); + int GetRunOffFlag() const; +private: + float nowJointsGoalList_[MAX_ARM_GOAL_COUNT][GOAL_DATA_LENGTH]; + int goalResultList_[MAX_ARM_GOAL_COUNT]; + int goalTypeList_[MAX_ARM_GOAL_COUNT]; + int64_t goalIndexList_[MAX_ARM_GOAL_COUNT]; + int startGoalIndex_; + int endGoalIndex_; + int goalFullFlag_; + int currentGoalRunOffFlag_; + + std::unordered_map goalIndex{MAX_ARM_GOAL_COUNT}; +}; + +#endif \ No newline at end of file diff --git a/rm_arm_control/include/kinematics.hpp b/rm_arm_control/include/kinematics.hpp new file mode 100644 index 0000000..c3e7a1c --- /dev/null +++ b/rm_arm_control/include/kinematics.hpp @@ -0,0 +1,19 @@ +#ifndef KINEMATICS_HPP +#define KINEMATICS_HPP +#include "rm_service.h" + +class ArmKinematics +{ +public: + ArmKinematics(RM_Service *rmService); + ArmKinematics(); + ~ArmKinematics(); + + int ForwardKinematics(float *jointAngles, float *endEffectorPose); + int InverseKinematics(const float *endEffectorPose, float *jointAngles); + +private: + RM_Service *rmService_; +}; + +#endif // KINEMATICS_HPP \ No newline at end of file diff --git a/rm_arm_control/include/rm_arm_driver.hpp b/rm_arm_control/include/rm_arm_driver.hpp new file mode 100644 index 0000000..08e8a0b --- /dev/null +++ b/rm_arm_control/include/rm_arm_driver.hpp @@ -0,0 +1,45 @@ +#ifndef RM_ARM_DRIVER_HPP +#define RM_ARM_DRIVER_HPP + +#include "arm_driver.hpp" +#include "rm_service.h" +#include "rm_define.h" + +enum { + RM_DRIVER_UNINIT = 0, + RM_DRIVER_INIT_OK, + RM_DRIVER_INIT_ERR +}; + +class RmArmDriver +{ +public: + RmArmDriver(); + ~RmArmDriver(); + + int Init(); + static int ArmMove(const float points[USED_ARM_DOF], int armId); + + using ApiLogFunc = void(*)(const char* message, va_list args); + void SetCustomApiLog(ApiLogFunc logFunc) {customApiLog_ = logFunc;} + + using RmArmStatusCallbackFun = void(*)(ArmStatusCallbackData *data); + void RegArmStatusCallback(RmArmStatusCallbackFun callback) { + armStatusCallback_ = callback; + } + + static RM_Service *rmService_; + +private: + int initFlag_; + static ApiLogFunc customApiLog_; + static RmArmStatusCallbackFun armStatusCallback_; + static rm_robot_handle *leftRobotHandle_; + static rm_robot_handle *rightRobotHandle_; + + static void CallbackRmRealtimeArmJointState(rm_realtime_arm_joint_state_t data); + int InitHandle(rm_robot_handle **robotHandle_, const char *robot_ip_address, int robot_port, rm_realtime_push_config_t *config); + static void api_log(const char* format, ...); +}; + +#endif // RM_ARM_DRIVER_HPP \ No newline at end of file diff --git a/rm_arm_control/include/rm_arm_handler.hpp b/rm_arm_control/include/rm_arm_handler.hpp new file mode 100644 index 0000000..7913e76 --- /dev/null +++ b/rm_arm_control/include/rm_arm_handler.hpp @@ -0,0 +1,67 @@ +#ifndef RM_ARM_HANDLER_HPP +#define RM_ARM_HANDLER_HPP + +#include +#include +#include +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/float64_multi_array.hpp" +#include "sensor_msgs/msg/joint_state.hpp" +#include "goal_manager.hpp" +#include "arm_define.h" +#include "arm_driver_define.hpp" +#include "rm_arm_simulator.hpp" + +typedef enum { + ARM_STATUS_INIT = 0, + ARM_STATUS_READY, + ARM_STATUS_MOVING, + ARM_STATUS_WAITING, + ARM_STATUS_ERROR +} ARM_STATUS_E; + +class RmArmHandler +{ +private: + std::shared_mutex rw_mutex_; + sem_t *sem_; + + GoalManager *goalManager_; + ArmDriver *driver_; +public: + RmArmHandler(ArmDriver *driver, int armType, sem_t *sem, KinematicsManager *trapezoidalTrajectory); + ~RmArmHandler(); + + KinematicsManager *trapezoidalTrajectory_; + int armType_; // 0:left 1:right + + void ArmDealCallBackInfo(ArmStatusCallbackData *data); + + float nowJoints_[USED_ARM_DOF]; + float nextJoints_[USED_ARM_DOF]; + + int AddNextPoint(float points[GOAL_DATA_LENGTH], const int64_t &index, int type); + int DeletePoint(int64_t index); + int64_t GetCurrentRunOffGoalIndex(); + int64_t GetCurrentGoalIndex(); + void ArmRun(int64_t timeStamp); + void ArmStop(int result = 0); + void ArmStopStart(int result); + void ArmMove(); + int GoalReached(); + + int AddNextPointFromPose(const float pose[POSE_DIMENSION], const int64_t &index, int type); + int AddNextPointFromPoseMoving(const float pose[POSE_DIMENSION], const int64_t &index); + int GetNextPointFromPoseStepping(const float pose[POSE_DIMENSION], float *joints); + + int StartNewTrajectory(); + + ARM_STATUS_E armStatus; +}; + + +#endif // RM_ARM_HANDLER_HPP diff --git a/rm_arm_control/include/rm_arm_node.hpp b/rm_arm_control/include/rm_arm_node.hpp new file mode 100644 index 0000000..339d0dc --- /dev/null +++ b/rm_arm_control/include/rm_arm_node.hpp @@ -0,0 +1,52 @@ +#ifndef RM_ARM_NODE_HPP +#define RM_ARM_NODE_HPP + +#include +#include "rclcpp_action/rclcpp_action.hpp" +#include "interfaces/action/arm.hpp" +#include +#include "arm_driver_define.hpp" +#include "rm_arm_handler.hpp" + +using namespace std::chrono_literals; +using std::placeholders::_1; + +using ArmAction = interfaces::action::Arm; +using GoalHandleArm = rclcpp_action::ServerGoalHandle; + +class RmArmNode: public rclcpp::Node +{ +public: + RmArmNode(ArmDriver *armDriver, Kinematics *kinematics); + ~RmArmNode(); + static RmArmHandler *leftArmHandler_; + static RmArmHandler *rightArmHandler_; + + static void CallbackRealtimeArmJointState(ArmStatusCallbackData *data); + +private: + sem_t sem_; + ArmDriver *armDriver_; + rclcpp_action::Server::SharedPtr action_server_; + static sensor_msgs::msg::JointState armStates; + + rclcpp_action::GoalResponse ArmActionGoal( + const rclcpp_action::GoalUUID & uuid, + std::shared_ptr goal); + rclcpp_action::CancelResponse ArmActionCancel( + const std::shared_ptr goal_handle); + void ArmActionAccepted(const std::shared_ptr goal_handle); + void ArmActionFeedback(int collision); + void ArmActionExecute(); + void ArmActionFinish(int64_t index, int result); + void ArmActionCheck(); + void StartNewGoal(RmArmHandler *handle); + + rclcpp::Subscription::SharedPtr robotDescriptionSub_; + static rclcpp::Publisher::SharedPtr armStatesPub_; + std::unordered_map> goal_handles_; + + void CallbackGetRobotDescription(const std_msgs::msg::String::SharedPtr msg); +}; + +#endif // RM_ARM_NODE_HPP diff --git a/rm_arm_control/include/rm_arm_simulator.hpp b/rm_arm_control/include/rm_arm_simulator.hpp new file mode 100644 index 0000000..80ce902 --- /dev/null +++ b/rm_arm_control/include/rm_arm_simulator.hpp @@ -0,0 +1,93 @@ +#ifndef RM_ARM_SIMULATOR_HPP +#define RM_ARM_SIMULATOR_HPP + +#include +#include +#include +#include +#include "arm_define.h" +#include "arm_driver_define.hpp" +#include "gjk_interface.hpp" + +#define ARM_COLLISION_CHECK_SIMPLE_CNT 2 + +typedef enum { + FRAME_CHANGE_TYPE_ARM_BASE_TO_ORI, + FRAME_CHANGE_TYPE_ORI_TO_ARM_BASE, + FRAME_CHANGE_TYPE_ARM_END_TO_ORI, + FRAME_CHANGE_TYPE_ORI_TO_ARM_END, + FRAME_CHANGE_TYPE_ERR +} FrameChangeTypeE; + +typedef std::vector Polyhedron; +struct CollisionStructure { + std::string link_name; // 所属链接名称 + std::string geometry_type; // 几何类型 + std::vector dimensions; // 几何尺寸/缩放因子 + std::vector origin_xyz; // 原点坐标 + std::vector origin_rpy; // 原点姿态 + std::string mesh_filename; // mesh文件路径(如STL) + std::vector mesh_bounds; // 网格边界盒 [min_x, max_x, min_y, max_y, min_z, max_z] + Polyhedron origin_points; +}; + +struct JointInfo { + std::string name; // 关节名称 + int type; // 关节类型 + int parent_link; // 父连杆 + int child_link; // 子连杆 + Eigen::Quaterniond rotationAll; + Eigen::Vector3d axis; // 关节轴 + Eigen::Vector3d offset; // 关节偏移 + Eigen::Quaterniond rotation; // 关节旋转 + double limit_lower; + double limit_upper; + double limit_v; + double limit_e; + double angle; // 关节角度 +}; + +enum { + SAFE = 0, + LEFT_ARM_COLLISION, + RIGHT_ARM_COLLISION, +}; + +class ArmSimulator +{ +public: + ArmSimulator(std_msgs::msg::String::SharedPtr urdf_string_ptr, float *left_now_joints, float *right_now_joints, + KinematicsManager *leftTrajectory, KinematicsManager *rightTrajectory); + ArmSimulator(std::string urdf_string, float *left_now_joints, float *right_now_joints, + KinematicsManager *leftTrajectory, KinematicsManager *rightTrajectory); + ~ArmSimulator(); + + int CheckCollision(); + int CheckJointsAngleLimit(float *joints); + int UpdateCollisionForNewGoal(int arm); + int AddPolyhedron(int id, const Polyhedron& poly); + int RemovePolyhedron(int id); + + int ChangeArmBaseFrameToArmEndPose(float *pose, int arm, int64_t frameTime); + int ChangeOriFrameToArmBasePose(float *pose, int arm); + int ChangeArmEndPoseToArmBaseFrame(float *pose, int arm, int64_t frameTime); + int ChangeArmBasePoseToOriFrame(float *pose, int arm); + + int GetFrameChange(float *pose, int arm, int64_t frameTime, JointInfo *jointInfo); + + KinematicsManager *leftTrajectory_; + KinematicsManager *rightTrajectory_; + + std::vector collision_structures_; + std::map jointMap_; + std::vector armPolyhedrons_[ARM_COLLISION_CHECK_SIMPLE_CNT]; + std::vector addedOBBs_[ARM_COLLISION_CHECK_SIMPLE_CNT]; + + int simpleUpdateIndex_; + float leftArmJoints_[ARM_COLLISION_CHECK_SIMPLE_CNT][USED_ARM_DOF]; + float rightArmJoints_[ARM_COLLISION_CHECK_SIMPLE_CNT][USED_ARM_DOF]; +private: + std::unordered_map addedPolyhedrons_; +}; + +#endif // RM_ARM_SIMULATOR_HPP \ No newline at end of file diff --git a/rm_arm_control/include/rm_driver_kinematics.hpp b/rm_arm_control/include/rm_driver_kinematics.hpp new file mode 100644 index 0000000..5eae206 --- /dev/null +++ b/rm_arm_control/include/rm_driver_kinematics.hpp @@ -0,0 +1,73 @@ +#ifndef RM_DRIVER_KINEMATICS_HPP +#define RM_DRIVER_KINEMATICS_HPP + +#include "arm_driver.hpp" +#include "arm_define.h" +#include "rm_service.h" + +enum { + RM_DRIVER_KINEMATICS_UNINIT = 0, + RM_DRIVER_KINEMATICS_INIT_OK, + RM_DRIVER_KINEMATICS_INIT_ERR +}; + +enum RmKinematicsStatus { + RM_KINEMATICS_STATUS_INIT = 0, + RM_KINEMATICS_STATUS_RUN, + RM_KINEMATICS_STATUS_END, +}; + +struct NodataTrajectory { + float start[ARM_DOF]; + float end[ARM_DOF]; + int currentStep; + + int runState; // 0: stop, 1: running + int goalType; + int armId; +}; + +class RmArmDriverAndKinematics +{ +public: + RmArmDriverAndKinematics(); + ~RmArmDriverAndKinematics(); + + int Init(); + static int ArmMove(const float points[USED_ARM_DOF], int armId); + + using ApiLogFunc = void(*)(const char* message, va_list args); + void SetCustomApiLog(ApiLogFunc logFunc) {customApiLog_ = logFunc;} + + using RmArmStatusCallbackFun = void(*)(ArmStatusCallbackData *data); + void RegArmStatusCallback(RmArmStatusCallbackFun callback) { + armStatusCallback_ = callback; + } + + void getAngleForCheckingInner(NodataTrajectory *trajectory, int timeStep, float *aimAngles); + void getAngleForCheckingOffset(NodataTrajectory *trajectory, int timeStepOffset, float *aimAngles); + int computeMovingTrajectory(NodataTrajectory *trajectory, const float *start, const float *end, int armId); + int computeSteppingTrajectory(NodataTrajectory *trajectory, const float *start, const float *speed, int armId); + int computePoseSteppingTrajectory(NodataTrajectory *trajectory, const float *start, const float *end, int armId); + int updateTrajectory(NodataTrajectory *trajectory, float *aimAngles); + void stopTrajectory(NodataTrajectory *trajectory); + int continuePoseSteppingTrajectory(NodataTrajectory *trajectory, const float *nowAngles, const float *direct); + + int ForwardKinematics(float *jointAngles, float *endEffectorPose); + int InverseKinematics(const float *endEffectorPose, float *jointAngles); + + static RM_Service *rmService_; + +private: + int initFlag_; + static ApiLogFunc customApiLog_; + static RmArmStatusCallbackFun armStatusCallback_; + static rm_robot_handle *leftRobotHandle_; + static rm_robot_handle *rightRobotHandle_; + + static void CallbackRmRealtimeArmJointState(rm_realtime_arm_joint_state_t data); + int InitHandle(rm_robot_handle **robotHandle_, const char *robot_ip_address, int robot_port, rm_realtime_push_config_t *config); + static void api_log(const char* format, ...); +}; + +#endif // RM_DRIVER_KINEMATICS_HPP \ No newline at end of file diff --git a/rm_arm_control/include/trajectory.hpp b/rm_arm_control/include/trajectory.hpp new file mode 100644 index 0000000..92a2aa5 --- /dev/null +++ b/rm_arm_control/include/trajectory.hpp @@ -0,0 +1,120 @@ +#ifndef TRAJECTORY_HPP +#define TRAJECTORY_HPP + +#include +#include "arm_define.h" +#include "trapezoidal_trajectory_kinematics.hpp" +#include "rm_driver_kinematics.hpp" + +template +class TrajectoryManager +{ +public: + TrajectoryManager(K *armKinematics) : armKinematics_(armKinematics) { + nowTrajectoryIndex_ = -1; + trajectoryFullFlag_ = 0; + } + TrajectoryManager(K *armKinematics, int armId) : armKinematics_(armKinematics), armId_(armId) { + nowTrajectoryIndex_ = -1; + trajectoryFullFlag_ = 0; + } + ~TrajectoryManager() {} + + int computeTrajectory(const float *start, const float *end, int type) { + T* newTrajectory = addTrajectory(); + if (type == GOAL_TYPE_MOVING) { + return armKinematics_->computeMovingTrajectory(newTrajectory, start, end, armId_); + } else if (type == GOAL_TYPE_POSE_STEPPING) { + return armKinematics_->computePoseSteppingTrajectory(newTrajectory, start, end, armId_); + } else { + return armKinematics_->computeSteppingTrajectory(newTrajectory, start, end, armId_); + } + return UNKNOWN_ERR; + } + + int updateTrajectory(int64_t startTime, float *aimAngles) { + if (nowTrajectoryIndex_ < 0) { + return OK; + } + if (trajectoryStartTime_[nowTrajectoryIndex_] == 0) { + trajectoryStartTime_[nowTrajectoryIndex_] = startTime; + } + return armKinematics_->updateTrajectory(&trajectoryHistory_[nowTrajectoryIndex_], aimAngles); + } + + int getAngleFromTime(float *aimAngles, int64_t timeStamp) { + if (nowTrajectoryIndex_ < 0) { + return OK; + } + int timeStep = 0; + int aimIndex = -1; + int startIndex = nowTrajectoryIndex_ + 1; + int endIndex = trajectoryFullFlag_ == 1 ? startIndex : 0; + do { + startIndex = (startIndex + MAX_TRAJECTORY_HISTORY - 1) % MAX_TRAJECTORY_HISTORY; + if (trajectoryStartTime_[startIndex] < timeStamp) { + aimIndex = startIndex; + timeStep = static_cast((timeStamp - trajectoryStartTime_[startIndex]) / ARM_FOLLOWING_PERIOD); + break; + } + } while (startIndex != endIndex); + + if (aimIndex == -1) { + return UNKNOWN_ERR; + } + armKinematics_->getAngleForCheckingInner(&trajectoryHistory_[aimIndex], timeStep, aimAngles); + return 0; + } + + void getAngleForChecking(float *aimAngles) { + if (nowTrajectoryIndex_ < 0) { + return; + } + T* nowTrajectory = &trajectoryHistory_[nowTrajectoryIndex_]; + armKinematics_->getAngleForCheckingOffset(nowTrajectory, ARM_FOLLOWING_CHECKING_STEP * 2, aimAngles); + } + + void getAngleForStarting(float *aimAngles) { + if (nowTrajectoryIndex_ < 0) { + return; + } + T* nowTrajectory = &trajectoryHistory_[nowTrajectoryIndex_]; + armKinematics_->getAngleForCheckingOffset(nowTrajectory, ARM_FOLLOWING_CHECKING_STEP, aimAngles); + } + + void stopTrajectory() { + armKinematics_->stopTrajectory(&trajectoryHistory_[nowTrajectoryIndex_]); + } + + int continuePoseSteppingTrajectory(const float *nowAngles, const float *direct) { + return armKinematics_->continuePoseSteppingTrajectory(&trajectoryHistory_[nowTrajectoryIndex_], nowAngles, direct); + } + + T* getNowTrajectory() { + if (nowTrajectoryIndex_ < 0) { + return nullptr; + } + return &trajectoryHistory_[nowTrajectoryIndex_]; + } + + K *armKinematics_; + +private: + T trajectoryHistory_[MAX_TRAJECTORY_HISTORY]; + int64_t trajectoryStartTime_[MAX_TRAJECTORY_HISTORY]; + int nowTrajectoryIndex_; + int trajectoryFullFlag_; + int armId_; + + T* addTrajectory() { + nowTrajectoryIndex_++; + if (nowTrajectoryIndex_ >= MAX_TRAJECTORY_HISTORY) { + nowTrajectoryIndex_ = 0; + trajectoryFullFlag_ = 1; + } + trajectoryStartTime_[nowTrajectoryIndex_] = 0; + return &trajectoryHistory_[nowTrajectoryIndex_]; + } +}; + +#endif // TRAJECTORY_HPP \ No newline at end of file diff --git a/rm_arm_control/include/trapezoidal_trajectory.hpp b/rm_arm_control/include/trapezoidal_trajectory.hpp new file mode 100644 index 0000000..cbcb322 --- /dev/null +++ b/rm_arm_control/include/trapezoidal_trajectory.hpp @@ -0,0 +1,68 @@ +#ifndef TRAPEZOIDAL_TRAJECTORY_HPP +#define TRAPEZOIDAL_TRAJECTORY_HPP + +#include +#include "arm_define.h" + +#define TRAJECTORY_COMPELETE 1 +#define TRAJECTORY_ONGOING 0 +#define TRAJECTORY_ERROR -1 + +#define STEPPING_UNIFORM_TIME_STAMP -1 + +struct Trajectory { + float startAngles[USED_ARM_DOF]; + float endAngles[USED_ARM_DOF]; + float aim_velocity[USED_ARM_DOF]; + float now_acceleration[USED_ARM_DOF]; + int64_t startTime; + int accelerate_time_step; + int uniform_time_step; + int goalType; + int current_time_step; + + int64_t stopTime; +}; + +class TrapezoidalTrajectory +{ +public: + TrapezoidalTrajectory(); + ~TrapezoidalTrajectory(); + + int computeTrajectory(const float *start, const float *end, int type); + int updateTrajectory(float *aimAngles); + int checkStartTrajectory(int64_t startTime); + int getAngleFromTime(float *aimAngles, int64_t timeStamp); + void getAngleForChecking(float *aimAngles); + void getAngleForStarting(float *aimAngles); + void stopTrajectory(); + + int updatePoseSteppingTrajectory(float *aimAngles); + int continuePoseSteppingTrajectory(float *nowAngles, float *aimAngles); + + Trajectory* getNowTrajectory() { + if (nowTrajectoryIndex_ < 0) { + return nullptr; + } + return &trajectoryHistory_[nowTrajectoryIndex_]; + } + +private: + float max_velocity_; + float max_acceleration_; + int max_accelerate_time_; + float max_accelerate_angle_; + float min_angle_for_pose_stepping_max_speed_; + + Trajectory trajectoryHistory_[MAX_TRAJECTORY_HISTORY]; + int nowTrajectoryIndex_; + int trajectoryFullFlag_; + + Trajectory* addTrajectory(); + void computeMovingTrajectory(Trajectory *newTrajectory, const float *start, const float *end); + void computeSteppingTrajectory(Trajectory *newTrajectory, const float *start, const float *end); + void computePoseSteppingTrajectory(Trajectory *newTrajectory, const float *start, const float *end); +}; + +#endif // TRAPEZOIDAL_TRAJECTORY_HPP \ No newline at end of file diff --git a/rm_arm_control/include/trapezoidal_trajectory_kinematics.hpp b/rm_arm_control/include/trapezoidal_trajectory_kinematics.hpp new file mode 100644 index 0000000..9294766 --- /dev/null +++ b/rm_arm_control/include/trapezoidal_trajectory_kinematics.hpp @@ -0,0 +1,50 @@ +#ifndef TRAPEZOIDAL_TRAJECTORY_KINEMATICS_HPP +#define TRAPEZOIDAL_TRAJECTORY_KINEMATICS_HPP + +#include "arm_define.h" +#include "rm_service.h" + +#define STEPPING_UNIFORM_TIME_STAMP -1 + +struct TrapezoidalTrajectory { + float startAngles[USED_ARM_DOF]; + float endAngles[USED_ARM_DOF]; + float aim_velocity[USED_ARM_DOF]; + float now_acceleration[USED_ARM_DOF]; + int accelerate_time_step; + int uniform_time_step; + int goalType; + int current_time_step; +}; + +class TrapezoidalTrajectoryKinematics +{ +public: + TrapezoidalTrajectoryKinematics(RM_Service *rmService); + TrapezoidalTrajectoryKinematics(); + ~TrapezoidalTrajectoryKinematics(); + + void getAngleForCheckingInner(TrapezoidalTrajectory *trajectory, int timeStep, float *aimAngles); + void getAngleForCheckingOffset(TrapezoidalTrajectory *trajectory, int timeStepOffset, float *aimAngles); + int computeMovingTrajectory(TrapezoidalTrajectory *trajectory, const float *start, const float *end, int armId); + int computeSteppingTrajectory(TrapezoidalTrajectory *trajectory, const float *start, const float *speed, int armId); + int computePoseSteppingTrajectory(TrapezoidalTrajectory *trajectory, const float *start, const float *pose, int armId); + int updateTrajectory(TrapezoidalTrajectory *trajectory, float *aimAngles); + void stopTrajectory(TrapezoidalTrajectory *trajectory); + int continuePoseSteppingTrajectory(TrapezoidalTrajectory *trajectory, const float *nowAngles, const float *direct); + + int ForwardKinematics(float *jointAngles, float *endEffectorPose); + int InverseKinematics(const float *endEffectorPose, float *jointAngles); +private: + RM_Service *rmService_; + + float max_velocity_; + float max_acceleration_; + int max_accelerate_time_; + float max_accelerate_angle_; + float min_angle_for_pose_stepping_max_speed_; + + int PoseSteppingFromNowAnglesAndDirectPose(float *nowAngles, const float *direct); +}; + +#endif // TRAPEZOIDAL_TRAJECTORY_KINEMATICS_HPP \ No newline at end of file diff --git a/rm_arm_control/launch/rm_arm_control.launch.py b/rm_arm_control/launch/rm_arm_control.launch.py new file mode 100644 index 0000000..cc72d8f --- /dev/null +++ b/rm_arm_control/launch/rm_arm_control.launch.py @@ -0,0 +1,72 @@ +# 导入 ROS 2 launch 相关模块 +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.substitutions import Command, FindExecutable, PathJoinSubstitution +from launch_ros.substitutions import FindPackageShare +from launch.actions import OpaqueFunction +import os + +def load_urdf(context, *args, **kwargs): + nodeList = [] + + # 获取包的共享目录路径(解析为实际字符串) + package_share = FindPackageShare(package='rm_arm_control').perform(context) + + # 构建URDF文件的实际路径 + urdf_path = PathJoinSubstitution( + [package_share, 'urdf', 'FHrobot.urdf'] # 替换为你的URDF路径 + ).perform(context) + + # 读取URDF文件内容 + with open(urdf_path, 'r') as f: + urdf_content = f.read() + + robot_controller = Node( + package='rm_arm_control', + executable='rm_arm_control', + name='rm_arm_control', + output='screen', + parameters=[{ + 'robot_description': urdf_content, + 'use_sim_time': False + }] + ) + nodeList.append(robot_controller) + + # 创建机器人状态发布器节点 + robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + parameters=[{'robot_description': urdf_content}] + ) + nodeList.append(robot_state_publisher) + + '''joint_state_gui = Node( + package='joint_state_publisher_gui', + executable='joint_state_publisher_gui', + ) + nodeList.append(joint_state_gui)''' + + # 创建RViz节点(可选) + rviz_node = Node( + package='rviz2', + executable='rviz2', + name='rviz2', + arguments=[ + '-d', os.path.join( + FindPackageShare('rm_arm_control').find('rm_arm_control'), + 'launch', 'robot_view.rviz' # 保存的RViz配置文件路径 + ) + ], + parameters=[{ + # 这里可以设置一些RViz参数 + }] + ) + nodeList.append(rviz_node) + + return nodeList + +def generate_launch_description(): + return LaunchDescription([ + OpaqueFunction(function=load_urdf) + ]) diff --git a/rm_arm_control/launch/robot_view.rviz b/rm_arm_control/launch/robot_view.rviz new file mode 100644 index 0000000..a0626bf --- /dev/null +++ b/rm_arm_control/launch/robot_view.rviz @@ -0,0 +1,239 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /RobotModel1 + Splitter Ratio: 0.5 + Tree Height: 549 + - 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 + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + LeftLink1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LeftLink2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LeftLink3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LeftLink4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LeftLink5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + LeftLink6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link Tree Style: Links in Alphabetic Order + RightLink1: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RightLink2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RightLink3: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RightLink4: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RightLink5: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RightLink6: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link_leftarm: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link_rightarm: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + world: + Alpha: 1 + Show Axes: false + Show Trail: false + Mass Properties: + Inertia: false + Mass: false + Name: RobotModel + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + 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: 10 + 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.785398006439209 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 1192 + Y: 203 diff --git a/rm_arm_control/meshes/arm_base_link.STL b/rm_arm_control/meshes/arm_base_link.STL new file mode 100644 index 0000000..0889070 Binary files /dev/null and b/rm_arm_control/meshes/arm_base_link.STL differ diff --git a/rm_arm_control/meshes/base_link.STL b/rm_arm_control/meshes/base_link.STL new file mode 100644 index 0000000..a4ff44c Binary files /dev/null and b/rm_arm_control/meshes/base_link.STL differ diff --git a/rm_arm_control/meshes/body_2_link.STL b/rm_arm_control/meshes/body_2_link.STL new file mode 100644 index 0000000..ddb2ecf Binary files /dev/null and b/rm_arm_control/meshes/body_2_link.STL differ diff --git a/rm_arm_control/meshes/body_link.STL b/rm_arm_control/meshes/body_link.STL new file mode 100644 index 0000000..26aed52 Binary files /dev/null and b/rm_arm_control/meshes/body_link.STL differ diff --git a/rm_arm_control/meshes/head_link.STL b/rm_arm_control/meshes/head_link.STL new file mode 100644 index 0000000..ebe95ab Binary files /dev/null and b/rm_arm_control/meshes/head_link.STL differ diff --git a/rm_arm_control/meshes/left_arm_1_link.STL b/rm_arm_control/meshes/left_arm_1_link.STL new file mode 100644 index 0000000..deeb401 Binary files /dev/null and b/rm_arm_control/meshes/left_arm_1_link.STL differ diff --git a/rm_arm_control/meshes/left_arm_2_link.STL b/rm_arm_control/meshes/left_arm_2_link.STL new file mode 100644 index 0000000..8c6950e Binary files /dev/null and b/rm_arm_control/meshes/left_arm_2_link.STL differ diff --git a/rm_arm_control/meshes/left_arm_3_link.STL b/rm_arm_control/meshes/left_arm_3_link.STL new file mode 100644 index 0000000..404b659 Binary files /dev/null and b/rm_arm_control/meshes/left_arm_3_link.STL differ diff --git a/rm_arm_control/meshes/left_arm_4_link.STL b/rm_arm_control/meshes/left_arm_4_link.STL new file mode 100644 index 0000000..c324906 Binary files /dev/null and b/rm_arm_control/meshes/left_arm_4_link.STL differ diff --git a/rm_arm_control/meshes/left_behind_hip_link.STL b/rm_arm_control/meshes/left_behind_hip_link.STL new file mode 100644 index 0000000..210d856 Binary files /dev/null and b/rm_arm_control/meshes/left_behind_hip_link.STL differ diff --git a/rm_arm_control/meshes/left_behind_leg_link.STL b/rm_arm_control/meshes/left_behind_leg_link.STL new file mode 100644 index 0000000..90629bf Binary files /dev/null and b/rm_arm_control/meshes/left_behind_leg_link.STL differ diff --git a/rm_arm_control/meshes/left_behind_wheel_link.STL b/rm_arm_control/meshes/left_behind_wheel_link.STL new file mode 100644 index 0000000..97f8519 Binary files /dev/null and b/rm_arm_control/meshes/left_behind_wheel_link.STL differ diff --git a/rm_arm_control/meshes/left_front_hip_link.STL b/rm_arm_control/meshes/left_front_hip_link.STL new file mode 100644 index 0000000..9514d8f Binary files /dev/null and b/rm_arm_control/meshes/left_front_hip_link.STL differ diff --git a/rm_arm_control/meshes/left_front_knee_link.STL b/rm_arm_control/meshes/left_front_knee_link.STL new file mode 100644 index 0000000..dead3d7 Binary files /dev/null and b/rm_arm_control/meshes/left_front_knee_link.STL differ diff --git a/rm_arm_control/meshes/left_front_roll_link.STL b/rm_arm_control/meshes/left_front_roll_link.STL new file mode 100644 index 0000000..64678b4 Binary files /dev/null and b/rm_arm_control/meshes/left_front_roll_link.STL differ diff --git a/rm_arm_control/meshes/left_front_wheel_link.STL b/rm_arm_control/meshes/left_front_wheel_link.STL new file mode 100644 index 0000000..9ae2902 Binary files /dev/null and b/rm_arm_control/meshes/left_front_wheel_link.STL differ diff --git a/rm_arm_control/meshes/left_shoulder_link.STL b/rm_arm_control/meshes/left_shoulder_link.STL new file mode 100644 index 0000000..f6875f8 Binary files /dev/null and b/rm_arm_control/meshes/left_shoulder_link.STL differ diff --git a/rm_arm_control/meshes/left_wrist_link.STL b/rm_arm_control/meshes/left_wrist_link.STL new file mode 100644 index 0000000..50d7168 Binary files /dev/null and b/rm_arm_control/meshes/left_wrist_link.STL differ diff --git a/rm_arm_control/meshes/link1.STL b/rm_arm_control/meshes/link1.STL new file mode 100644 index 0000000..9e488ed Binary files /dev/null and b/rm_arm_control/meshes/link1.STL differ diff --git a/rm_arm_control/meshes/link2.STL b/rm_arm_control/meshes/link2.STL new file mode 100644 index 0000000..7c40979 Binary files /dev/null and b/rm_arm_control/meshes/link2.STL differ diff --git a/rm_arm_control/meshes/link3.STL b/rm_arm_control/meshes/link3.STL new file mode 100644 index 0000000..de9e6b6 Binary files /dev/null and b/rm_arm_control/meshes/link3.STL differ diff --git a/rm_arm_control/meshes/link4.STL b/rm_arm_control/meshes/link4.STL new file mode 100644 index 0000000..80ce2f4 Binary files /dev/null and b/rm_arm_control/meshes/link4.STL differ diff --git a/rm_arm_control/meshes/link5.STL b/rm_arm_control/meshes/link5.STL new file mode 100644 index 0000000..d40ecc3 Binary files /dev/null and b/rm_arm_control/meshes/link5.STL differ diff --git a/rm_arm_control/meshes/link6.STL b/rm_arm_control/meshes/link6.STL new file mode 100644 index 0000000..b67bf2b Binary files /dev/null and b/rm_arm_control/meshes/link6.STL differ diff --git a/rm_arm_control/meshes/right_arm_1_link.STL b/rm_arm_control/meshes/right_arm_1_link.STL new file mode 100644 index 0000000..be8ece3 Binary files /dev/null and b/rm_arm_control/meshes/right_arm_1_link.STL differ diff --git a/rm_arm_control/meshes/right_arm_2_link.STL b/rm_arm_control/meshes/right_arm_2_link.STL new file mode 100644 index 0000000..e392f57 Binary files /dev/null and b/rm_arm_control/meshes/right_arm_2_link.STL differ diff --git a/rm_arm_control/meshes/right_arm_3_link.STL b/rm_arm_control/meshes/right_arm_3_link.STL new file mode 100644 index 0000000..ae4603c Binary files /dev/null and b/rm_arm_control/meshes/right_arm_3_link.STL differ diff --git a/rm_arm_control/meshes/right_arm_4_link.STL b/rm_arm_control/meshes/right_arm_4_link.STL new file mode 100644 index 0000000..892070f Binary files /dev/null and b/rm_arm_control/meshes/right_arm_4_link.STL differ diff --git a/rm_arm_control/meshes/right_behind_hip_link.STL b/rm_arm_control/meshes/right_behind_hip_link.STL new file mode 100644 index 0000000..67a3ca3 Binary files /dev/null and b/rm_arm_control/meshes/right_behind_hip_link.STL differ diff --git a/rm_arm_control/meshes/right_behind_leg_link.STL b/rm_arm_control/meshes/right_behind_leg_link.STL new file mode 100644 index 0000000..8f728eb Binary files /dev/null and b/rm_arm_control/meshes/right_behind_leg_link.STL differ diff --git a/rm_arm_control/meshes/right_behind_wheel_link.STL b/rm_arm_control/meshes/right_behind_wheel_link.STL new file mode 100644 index 0000000..0d54e2f Binary files /dev/null and b/rm_arm_control/meshes/right_behind_wheel_link.STL differ diff --git a/rm_arm_control/meshes/right_front_hip_link.STL b/rm_arm_control/meshes/right_front_hip_link.STL new file mode 100644 index 0000000..80f5aeb Binary files /dev/null and b/rm_arm_control/meshes/right_front_hip_link.STL differ diff --git a/rm_arm_control/meshes/right_front_knee_link.STL b/rm_arm_control/meshes/right_front_knee_link.STL new file mode 100644 index 0000000..ecdaa9c Binary files /dev/null and b/rm_arm_control/meshes/right_front_knee_link.STL differ diff --git a/rm_arm_control/meshes/right_front_roll_link.STL b/rm_arm_control/meshes/right_front_roll_link.STL new file mode 100644 index 0000000..0bdfe01 Binary files /dev/null and b/rm_arm_control/meshes/right_front_roll_link.STL differ diff --git a/rm_arm_control/meshes/right_front_wheel_link.STL b/rm_arm_control/meshes/right_front_wheel_link.STL new file mode 100644 index 0000000..d862d4d Binary files /dev/null and b/rm_arm_control/meshes/right_front_wheel_link.STL differ diff --git a/rm_arm_control/meshes/right_shoulder_link.STL b/rm_arm_control/meshes/right_shoulder_link.STL new file mode 100644 index 0000000..5280fb9 Binary files /dev/null and b/rm_arm_control/meshes/right_shoulder_link.STL differ diff --git a/rm_arm_control/meshes/right_wrist_link.STL b/rm_arm_control/meshes/right_wrist_link.STL new file mode 100644 index 0000000..fca3aed Binary files /dev/null and b/rm_arm_control/meshes/right_wrist_link.STL differ diff --git a/rm_arm_control/package.xml b/rm_arm_control/package.xml new file mode 100644 index 0000000..240f894 --- /dev/null +++ b/rm_arm_control/package.xml @@ -0,0 +1,25 @@ + + + + rm_arm_control + 1.0.0 + rm_arm_control package + Your Name + Apache-2.0 + + ament_cmake + interfaces + gjk_interface + rclcpp + rclcpp_action + moveit_core + moveit_ros_planning_interface + sensor_msgs + geometry_msgs + nav_msgs + ros2launch + + + ament_cmake + + diff --git a/rm_arm_control/readme.md b/rm_arm_control/readme.md new file mode 100644 index 0000000..2745535 --- /dev/null +++ b/rm_arm_control/readme.md @@ -0,0 +1,258 @@ +# RMDemo_MovejCANFD + +## **1. 项目介绍** +本项目是一个使用睿尔曼C开发包,完成工程完成读取demo下的关节角度轨迹文件,按照10ms的周期进行透传,机械臂可以稳定运行,不同型号机械臂的透传轨迹文件,注册机械臂实时状态的回调函数,透传过程中,可以实时获取机械臂当前角度。 + +## **2. 代码结构** +``` +RMDemo_MovejCANFD +├── build # CMake构建生成的输出目录(如Makefile、构建文件等) +├── cmake # CMake模块和脚本的存放目录 +│ ├── ... +├── data +│ └── robot_log.txt # 日志、轨迹文件等数据文件目录(在执行过程中生成) +├── include # 自定义头文件存放目录 +├── Robotic_Arm 睿尔曼机械臂二次开发包 +│ ├── include +│ │ ├── rm_define.h # 机械臂的定义 +│ │ └── rm_interface.h # 机械臂 API 的接口头文件 +│ ├── lib +│ │ ├── api_c.dll # Windows 的 API 库 +│ │ ├── api_c.lib # Windows 的 API 库 +│ │ └── libapi_c.so # Linux 的 API 库 +├── src +│ ├── main.c # 主函数 +├── CMakeLists.txt # 项目的顶层CMake配置文件 +├── readme.md # 为示例工程提供详细的文档 +├── run.bat # 快速运行脚本, Windows为bat脚本 +└── run.sh # 快速运行脚本, linux为shell脚本 + +``` + +## **3. 系统要求** + +- 操作系统:Ubuntu 18.04或更高版本 +- 编译器:GCC 7.5或更高版本 (或任何其他兼容的C编译器) +- 依赖库: + - CMake 3.10或更高版本 + - RMAPI库(包含在 `Robotic_Arm/lib`目录中) + + +## **4. 安装说明** + +1. 克隆项目到本地: + + ```bash + + ``` + +2. 构建项目: + Linux下: + cmake: + ```bash + mkdir build + cd build + cmake .. + make + + ``` + + 如果是GC编译的话 : + ```bash + #!/bin/bash + # 编译并链接 + gcc -I./include -I./Robotic_Arm/include -L./Robotic_Arm/lib -Wl,-rpath=./Robotic_Arm/lib -DDATA_FILE_PATH=\"$(pwd)/data/RM65\&RM63_canfd_data.txt\" -o RMDemo_MovejCANFD src/main.c -lapi_c + + # 检查编译是否成功 + if [ $? -eq 0 ]; then + # 设置LD_LIBRARY_PATH环境变量 + export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:./Robotic_Arm/lib + + # 运行编译后的可执行文件 + ./RMDemo_MovejCANFD + else + echo "编译失败" + fi + ``` + + +## **5. 注意事项** + +该Demo以RM65-B型号机械臂为例,请根据实际情况修改代码中的数据。 + +## **6. 使用指南** + +### **1. 快速运行** + +按照以下步骤快速运行代码: + +1. **配置机械臂IP地址**:打开 `main.c` 文件,在 `main` 函数中修改 `robot_ip_address` 类的初始化参数为当前机械臂的IP地址,默认IP地址为 `"192.168.1.18"`。 + + ```C + const char *robot_ip_address = "192.168.1.18"; + int robot_port = 8080; + rm_robot_handle *robot_handle = rm_create_robot_arm(robot_ip_address, robot_port); + ``` +2. **命令行运行**:在终端进入 `RMDemo_MovejCANFD` 目录,输入以下命令运行 C程序: + +2.1 Linux下 +* ```bash + chmod +x run.sh + ./run.sh + ``` + +2.2 Windows下: 双击运行 run.bat + +2.3 **选择对应型号轨迹文件**: +- 在方法中`demo_movej_canfd`中: + ```C + void demo_movej_canfd(rm_robot_handle* handle) { + printf("Trying to open file: %s\n", DATA_FILE_PATH); + + FILE* file = fopen(DATA_FILE_PATH, "r"); + if (!file) { + perror("Failed to open file"); + return; + } + + float points[MAX_POINTS][ARM_DOF]; + int point_count = 0; + while (fscanf(file, "%f,%f,%f,%f,%f,%f,%f", + &points[point_count][0], &points[point_count][1], &points[point_count][2], + &points[point_count][3], &points[point_count][4], &points[point_count][5], + &points[point_count][6]) == ARM_DOF) { + point_count++; + } + + ``` + - ECO65:ECO65_canfd_data.txt + - RM65&RML63-Ⅱ:RM65&RM63_canfd_data.txt + - RM75:RM75_canfd_data.txt + - DATA_FILE_PATH 为了跨平台在[CMakeLists.txt](CMakeLists.txt) 里面通过 # 将数据文件路径定义为预处理器宏 + add_definitions(-DDATA_FILE_PATH="${CMAKE_CURRENT_SOURCE_DIR}/data/RM65&RM63_canfd_data.txt") + - + + +### **2. 代码说明** + +下面是 `main.c` 文件的主要功能: + +- **连接机械臂** + ```C + rm_robot_handle *robot_handle = rm_create_robot_arm(robot_ip_address, robot_port); + ``` + 连接到指定IP和端口的机械臂。 + +- **获取API版本** + + ```C + char *api_version = rm_api_version(); + printf("API Version: %s.\n", api_version); + ``` + 获取并显示API版本。 + + +- **配置实时推送** + + ```C + rm_realtime_push_config_t config = {5, true, 8089, 0, "192.168.1.88"}; + int result = rm_set_realtime_push(robot_handle, config); + ``` + +- **读取关节角度轨迹文件并进行透传** + + ```C + demo_movej_canfd(robot_handle) + ``` + + +- **断开机械臂连接** + + ```C + disconnect_robot_arm(robot_handle); + ``` + +### **3. 运行结果示例** + +运行脚本后,输出结果如下所示: + +``` +API Version: 0.3.0. +Robot handle created successfully: 1 +Joint positions: +0.01 -21.32 -78.51 -0.03 -80.17 0.02 +Joint positions: +0.01 -21.32 -78.51 -0.03 -80.17 0.02 +Joint positions: +0.01 -21.32 -78.51 -0.03 -80.17 0.02 +Joint positions: +0.01 -21.32 -78.51 -0.03 -80.17 0.02 +Joint positions: +0.01 -21.32 -78.51 -0.03 -80.17 0.02 +Joint positions: +0.01 -21.32 -78.51 -0.03 -80.17 0.02 +Joint positions: +0.01 -21.32 -78.51 -0.03 -80.17 0.02 +Successfully set realtime push configuration. +Current state: -53.000 +Current angles: 0.013 -21.323 -78.511 -0.034 -80.170 0.020 +Current state: 0 +Current state: 0 +Error Code: 0 +Arm IP: 192.168.1.18 +Arm Error: 0 +Joint Position: + 0.013 + -21.323 + -78.511 + -0.034 + -80.170 + 0.020 +Force Sensor: + Coordinate: 888729056 +System Error: 0 +Waypoint: + Euler: [3.141, 0.000, 0.000] + Position: [0.300, -0.000, 0.299] + Quat: [0.000, 1.000, -0.000, -0.000] + .... + 176.12 -128.64 133.60 176.12 126.63 356.12 +Pass-through completed + +The motion is complete, the arm is in place. +Motion result: 1 +Current device: 0 +Is the next trajectory connected: 0 +movej_cmd joint movement 1: 0 +... +Joint positions: +-0.00 0.00 0.00 0.00 0.00 -0.00 +INFO: disconnect_robot_arm: Operation successful + +``` +#### 2)运行脚本后,运行轨迹从上至下如下图所示: + +![moveCANFD](moveCANFD.gif) + + +## **6. 许可证信息** + +* 本项目遵循MIT许可证。 + +## **7. 常见问题解答(FAQ)** + + +- **Q:** 如何解决编译错误? + **A:** 请确保您的编译器版本和依赖库满足系统要求,并按照安装说明重新配置环境。 + +- **Q:** 如何连接机器人? + **A:** 请参考示例代码中的连接步骤,确保机器人IP地址和端口正确配置。 + +- **Q:** UDP数据推送接口收不到数据? + **A:** 检查线程模式、是否使能推送数据、IP以及防火墙 + +- - **Q:** Trying to open file: C:/Users/dell/Videos/710/RMDemo_MovejCANFD/data/RM65&RM63_canfd_data.txt No valid points data found in file? + **A:** #define ARM_DOF 6 在 RMDemo_MovejCANFD\include\utils.h 下是否未定义 + + + diff --git a/rm_arm_control/run.sh b/rm_arm_control/run.sh new file mode 100755 index 0000000..11d3387 --- /dev/null +++ b/rm_arm_control/run.sh @@ -0,0 +1,27 @@ +#!/bin/bash + +# 设置构建目录 +BUILD_DIR=build + +# 如果构建目录存在,则删除 +if [ -d "$BUILD_DIR" ]; then + rm -rf $BUILD_DIR +fi + +# 创建构建目录 +mkdir $BUILD_DIR + +# 进入构建目录 +cd $BUILD_DIR + +# 运行CMake配置 +cmake .. + +# 运行make进行编译 +make + +# 返回根目录 +cd .. + +# 运行编译后的可执行文件 +./build/RMDemo_MovejCANFD \ No newline at end of file diff --git a/rm_arm_control/simulator/kinematics.cpp b/rm_arm_control/simulator/kinematics.cpp new file mode 100644 index 0000000..d2d6d21 --- /dev/null +++ b/rm_arm_control/simulator/kinematics.cpp @@ -0,0 +1,80 @@ +#include "kinematics.hpp" +#include "arm_define.h" +#include +#include + +ArmKinematics::ArmKinematics(RM_Service *rmService) : + rmService_(rmService) +{ + rm_robot_arm_model_e Mode = RM_MODEL_RM_65_E; + rm_force_type_e Type = RM_MODEL_RM_B_E; + rm_algo_init_sys_data(Mode, Type); +} + +ArmKinematics::ArmKinematics() +{ + rmService_ = new RM_Service(); + int result = rmService_->rm_init(RM_TRIPLE_MODE_E); + if (result != 0) { + throw std::runtime_error("Failed to init rm."); + return; + } + + rm_robot_arm_model_e Mode = RM_MODEL_RM_65_E; + rm_force_type_e Type = RM_MODEL_RM_B_E; + rm_algo_init_sys_data(Mode, Type); +} + +ArmKinematics::~ArmKinematics() +{ + delete rmService_; +} + +int ArmKinematics::ForwardKinematics(float *jointAngles, float *endEffectorPose) +{ + if (!rmService_) + { + return UNKNOWN_ERR; // Error: RM_Service not initialized + } + + // Call the RM_Service's ForwardKinematics method + rm_pose_t pose = rmService_->rm_algo_forward_kinematics(NULL, jointAngles); + endEffectorPose[POSE_POSITION_X] = pose.position.x; + endEffectorPose[POSE_POSITION_Y] = pose.position.y; + endEffectorPose[POSE_POSITION_Z] = pose.position.z; + endEffectorPose[POSE_QUATERNION_X] = pose.quaternion.x; + endEffectorPose[POSE_QUATERNION_Y] = pose.quaternion.y; + endEffectorPose[POSE_QUATERNION_Z] = pose.quaternion.z; + endEffectorPose[POSE_QUATERNION_W] = pose.quaternion.w; + return 0; +} + +int ArmKinematics::InverseKinematics(const float *endEffectorPose, float *jointAngles) +{ + if (!rmService_) + { + return UNKNOWN_ERR; // Error: RM_Service not initialized + } + + float nowJoints_[ARM_DOF] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; + for (int i = 0; i < USED_ARM_DOF; i++) { + nowJoints_[i] = jointAngles[i]; + } + rm_inverse_kinematics_params_t inverse_params; + memcpy(inverse_params.q_in, nowJoints_, sizeof(nowJoints_)); + inverse_params.q_pose.position.x = endEffectorPose[POSE_POSITION_X]; + inverse_params.q_pose.position.y = endEffectorPose[POSE_POSITION_Y]; + inverse_params.q_pose.position.z = endEffectorPose[POSE_POSITION_Z]; + inverse_params.q_pose.quaternion.x = endEffectorPose[POSE_QUATERNION_X]; + inverse_params.q_pose.quaternion.y = endEffectorPose[POSE_QUATERNION_Y]; + inverse_params.q_pose.quaternion.z = endEffectorPose[POSE_QUATERNION_Z]; + inverse_params.q_pose.quaternion.w = endEffectorPose[POSE_QUATERNION_W]; + inverse_params.flag = 0; + + int result = rmService_->rm_algo_inverse_kinematics(NULL, inverse_params, nowJoints_); + if (result != 0){ + return ARM_AIM_CANNOT_REACH; // Inverse kinematics failed + } + memcpy(jointAngles, nowJoints_, sizeof(float) * USED_ARM_DOF); + return 0; +} \ No newline at end of file diff --git a/rm_arm_control/simulator/rm_arm_simulator.cpp b/rm_arm_control/simulator/rm_arm_simulator.cpp new file mode 100644 index 0000000..2b463f5 --- /dev/null +++ b/rm_arm_control/simulator/rm_arm_simulator.cpp @@ -0,0 +1,1138 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "rm_arm_simulator.hpp" + +using namespace Eigen; +#define MAX_ARM_POLYHEDRONS_CNT 8 +#define ARM_POLYHEDRONS_POINT 8 +#define ARM_POLYHEDRONS_CNT 15 + +static const bool LinkCollisionDetecMatrix[(USED_ARM_DOF + 1) * 2][ARM_POLYHEDRONS_CNT] = { + // BASE L1 L2 L3 L4 L5 L6 BASE R1 R2 R3 R4 R5 R6 BASE + { false, false, false, false, false, false, false, false, false, false, false, false, false, false, false}, // BASE + { false, false, false, false, false, true, true, false, true, true, true, true, true, true, false}, // L1 + { false, false, false, false, false, true, true, false, true, true, true, true, true, true, false}, // L2 + { false, false, false, false, false, false, false, false, true, true, true, true, true, true, true}, // L3 + { false, false, false, false, false, false, false, false, true, true, true, true, true, true, true}, // L4 + { false, true, true, false, false, false, false, false, true, true, true, true, true, true, true}, // L5 + { false, true, true, false, false, false, false, false, true, true, true, true, true, true, true}, // L6 + { false, false, false, false, false, false, false, false, false, false, false, false, false, false, false}, // BASE + { false, true , true , true , true , true , true , false , false , false , false , false, true, true, false}, // R1 + { false, true , true , true , true , true , true , false , false , false , false , false , true , true, false}, // R2 + { false, true , true , true , true , true , true , false , false , false , false , false , false , false, true}, // R3 + { false, true , true , true , true , true , true , false , false , false , false , false , false , false, true}, // R4 + { false, true , true , true , true , true , true , false , true , true , false , false , false , false, true}, // R5 + { false, true , true , true , true , true , true , false , true , true , false , false , false , false, true} // R6 +}; + +static std::map g_linkMap = { + {"base_link_leftarm", 0}, + {"LeftLink1", 1}, + {"LeftLink2", 2}, + {"LeftLink3", 3}, + {"LeftLink4", 4}, + {"LeftLink5", 5}, + {"LeftLink6", 6}, + {"base_link_rightarm", 7}, + {"RightLink1", 8}, + {"RightLink2", 9}, + {"RightLink3", 10}, + {"RightLink4", 11}, + {"RightLink5", 12}, + {"RightLink6", 13}, + {"body_2_link", 14} +}; + +enum OriginBoxIndex { + BASE = 14, + LEFT = 0, + RIGHT = 7 +}; + +using namespace Eigen; + +std::vector g_origin = { + Vector3d(0, 0, 0), // BASE + Vector3d(0, 0, 0), // L1 + Vector3d(0, 0, 0), // L2 + Vector3d(0, 0, 0), // L3 + Vector3d(0, 0, 0), // L4 + Vector3d(0, 0, 0), // L5 + Vector3d(0, 0, 0), // L6 + Vector3d(0, 0, 0), // BASE + Vector3d(0, 0, 0), // R1 + Vector3d(0, 0, 0), // R2 + Vector3d(0, 0, 0), // R3 + Vector3d(0, 0, 0), // R4 + Vector3d(0, 0, 0), // R5 + Vector3d(0, 0, 0) // R6 +}; + +std::vector g_offset = { + Vector3d(0, 0, 0), // BASE + Vector3d(0, 0, 0), // L1 + Vector3d(0, 0, 0), // L2 + Vector3d(0, 0, 0), // L3 + Vector3d(0, 0, 0), // L4 + Vector3d(0, 0, 0), // L5 + Vector3d(0, 0, 0), // L6 + Vector3d(0, 0, 0), // BASE + Vector3d(0, 0, 0), // R1 + Vector3d(0, 0, 0), // R2 + Vector3d(0, 0, 0), // R3 + Vector3d(0, 0, 0), // R4 + Vector3d(0, 0, 0), // R5 + Vector3d(0, 0, 0) // R6 +}; + +std::vector g_dir = { + Vector3d(0, 0, 0), // BASE + Vector3d::UnitX() * -1, // L1 + Vector3d::UnitZ(), // L2 + Vector3d::UnitZ(), // L3 + Vector3d::UnitX() * -1, // L4 + Vector3d::UnitZ(), // L5 + Vector3d::UnitX() * -1, // L6 + Vector3d(0, 0, 0), // BASE + Vector3d::UnitX(), // R1 + Vector3d::UnitZ() * -1, // R2 + Vector3d::UnitZ() * -1, // R3 + Vector3d::UnitX(), // R4 + Vector3d::UnitZ() * -1, // R5 + Vector3d::UnitX(), // R6 +}; + +static int CheckCollisionInner(std::vector *addedOBBs, std::vector *addedOBBsNext_); + +static void InitArmSinglePolyhedron(ArmSimulator *simulator, int index, Polyhedron *poly, + Vector3d &origin, const Vector3d &offset, const Matrix3d &rotation) +{ + float length = simulator->collision_structures_[index].dimensions[0]; // 长度(沿u方向) + float width = simulator->collision_structures_[index].dimensions[1]; // 宽度(沿v方向) + float height = simulator->collision_structures_[index].dimensions[2]; // 高度(沿法向量方向) + + Vector3d lenVec = rotation * Vector3d(length, 0, 0); // 长度方向 + Vector3d widVec = rotation * Vector3d(0, width, 0); // 宽度方向 + Vector3d heiVec = rotation * Vector3d(0, 0, height); // 高度方向 + + Vector3d bottomLeft = rotation * offset + origin; + + (*poly)[0] = bottomLeft; + (*poly)[1] = bottomLeft + lenVec; + (*poly)[2] = bottomLeft + widVec; + (*poly)[3] = (*poly)[1] + widVec; + (*poly)[4] = bottomLeft + heiVec; + (*poly)[5] = (*poly)[1] + heiVec; + (*poly)[6] = (*poly)[2] + heiVec; + (*poly)[7] = (*poly)[3] + heiVec; + if (index < BASE - 1) { + origin = origin + rotation * g_origin[index + 1]; + } +} + +static void InitArmPolyhedronsList(ArmSimulator *simulator) +{ + for (int i = 0; i < ARM_COLLISION_CHECK_SIMPLE_CNT; i++) { + simulator->armPolyhedrons_[i].resize(ARM_POLYHEDRONS_CNT); + simulator->addedOBBs_[i].resize(ARM_POLYHEDRONS_CNT); + simulator->armPolyhedrons_[i][BASE].clear(); + } + + /*RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "origin:"); + for (int i = 0; i < BASE; ++i) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%d: %.4f %.4f %.4f", i, g_origin[i].x(), g_origin[i].y(), g_origin[i].z()); + } + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "offset:"); + for (int i = 0; i < BASE; ++i) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%d: %.4f %.4f %.4f", i, g_offset[i].x(), g_offset[i].y(), g_offset[i].z()); + }*/ + + for (int simple = 0; simple < ARM_COLLISION_CHECK_SIMPLE_CNT; simple++) { + for (int i = 0; i < ARM_POLYHEDRONS_CNT; i++) { + for (int j = 0; j < ARM_POLYHEDRONS_POINT; j++) { + simulator->armPolyhedrons_[simple][i].push_back(Vector3d(0, 0, 0)); + } + } + } + for (int simple = 0; simple < ARM_COLLISION_CHECK_SIMPLE_CNT; simple++) { + std::vector *armPolyhedrons = &(simulator->armPolyhedrons_[simple]); + Vector3d offset_temp = {0, 0 ,0}; + Vector3d origin_point_offset = {0, 0 ,0}; + if (simulator->collision_structures_[BASE].geometry_type == "box") { + origin_point_offset = Vector3d(-simulator->collision_structures_[BASE].dimensions[0] / 2, + -simulator->collision_structures_[BASE].dimensions[1] / 2, + -simulator->collision_structures_[BASE].dimensions[2] / 2); + } else if (simulator->collision_structures_[BASE].geometry_type == "mesh") { + origin_point_offset = Vector3d(simulator->collision_structures_[BASE].mesh_bounds[0], + simulator->collision_structures_[BASE].mesh_bounds[2], + simulator->collision_structures_[BASE].mesh_bounds[4]); + } + Matrix3d rotation = Matrix3d::Identity(); + InitArmSinglePolyhedron(simulator, BASE, &(*armPolyhedrons)[BASE], + offset_temp, + origin_point_offset, + rotation); + simulator->addedOBBs_[simple][BASE] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[BASE], + simulator->collision_structures_[BASE].dimensions[0], + simulator->collision_structures_[BASE].dimensions[1], + simulator->collision_structures_[BASE].dimensions[2]); + + Vector3d offset_vec = g_origin[LEFT]; + for (int i = LEFT; i < RIGHT; i++) { + InitArmSinglePolyhedron(simulator, i, &(*armPolyhedrons)[i], + offset_vec, + g_offset[i], + rotation); + simulator->addedOBBs_[simple][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[i], + simulator->collision_structures_[i].dimensions[0], + simulator->collision_structures_[i].dimensions[1], + simulator->collision_structures_[i].dimensions[2]); + } + + offset_vec = g_origin[RIGHT]; + for (int i = RIGHT; i < BASE; i++) { + InitArmSinglePolyhedron(simulator, i, &(*armPolyhedrons)[i], + offset_vec, + g_offset[i], + rotation); + simulator->addedOBBs_[simple][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[i], + simulator->collision_structures_[i].dimensions[0], + simulator->collision_structures_[i].dimensions[1], + simulator->collision_structures_[i].dimensions[2]); + } + } + for (int i = LEFT; i <= BASE; ++i) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Link %d polyhedron points:", i); + for (int j = 0; j < ARM_POLYHEDRONS_POINT; ++j) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%d: %.4f %.4f %.4f", j, + simulator->armPolyhedrons_[0][i][j].x(), + simulator->armPolyhedrons_[0][i][j].y(), + simulator->armPolyhedrons_[0][i][j].z()); + } + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "---------------------"); + } +} + +static int RemakeCollisionStructureList(ArmSimulator *simulator, + std::vector &collision_structures_temp) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "共提取到 %zu 个碰撞结构", collision_structures_temp.size()); + simulator->collision_structures_.resize(g_linkMap.size()); + for (const auto& col : collision_structures_temp) { + int index = g_linkMap[col.link_name]; + simulator->collision_structures_[index] = col; + } + for (const auto& col : simulator->collision_structures_) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "链接: %s, 类型: %s, ", + col.link_name.c_str(), + col.geometry_type.c_str()); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "尺寸: %.2f x %.2f x %.2f", + col.dimensions[0], + col.dimensions[1], + col.dimensions[2]); + } + return 0; +} + +static double toRadians(float degrees) { + return (static_cast(degrees)) * (M_PI / 180.0); +} + +static int UpdateJointAngles(ArmSimulator *simulator) +{ + if (simulator == NULL) return -1; + int simple = simulator->simpleUpdateIndex_; + simulator->leftTrajectory_->getAngleForChecking + (simulator->leftArmJoints_[simple]); + simulator->rightTrajectory_->getAngleForChecking + (simulator->rightArmJoints_[simple]); + if (simulator->CheckJointsAngleLimit(simulator->leftArmJoints_[simple]) != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "AngleDirectMove joints limit error."); + return ARM_AIM_CANNOT_REACH; + } + if (simulator->CheckJointsAngleLimit(simulator->rightArmJoints_[simple]) != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "AngleDirectMove joints limit error."); + return ARM_AIM_CANNOT_REACH; + } + return 0; +} + +static void UpdateArmPolyhedrons(ArmSimulator *simulator) +{ + if (simulator == NULL) return; + int simple = simulator->simpleUpdateIndex_; + std::vector *armPolyhedrons = &(simulator->armPolyhedrons_[simple]); + + Vector3d offset_vec = g_origin[LEFT] + g_origin[LEFT + 1]; + Vector3d normal = Vector3d(-1, 0, 0); + // Matrix3d rotation = AngleAxisf(-M_PI / 2, Vector3d::UnitX()) * Matrix3d::Identity(); + Matrix3d rotation = Matrix3d::Identity(); + Vector3d new_normal; + for (int i = LEFT + 1; i < RIGHT; i++) { + double angleRad = toRadians(simulator->leftArmJoints_[simple][i - LEFT - 1]); + rotation = AngleAxisd(angleRad, rotation * g_dir[i]) * rotation; + new_normal = rotation * normal; + /*RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Link %d normal: (%.4f, %.4f, %.4f) rotation: " + "(%.4f, %.4f, %.4f)" + "(%.4f, %.4f, %.4f)" + "(%.4f, %.4f, %.4f)", + i, new_normal.x(), new_normal.y(), new_normal.z(), + rotation(0, 0), rotation(0, 1), rotation(0, 2), + rotation(1, 0), rotation(1, 1), rotation(1, 2), + rotation(2, 0), rotation(2, 1), rotation(2, 2));*/ + InitArmSinglePolyhedron(simulator, i, &(*armPolyhedrons)[i], + offset_vec, + g_offset[i], + rotation); + simulator->addedOBBs_[simple][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[i], + simulator->collision_structures_[i].dimensions[0], + simulator->collision_structures_[i].dimensions[1], + simulator->collision_structures_[i].dimensions[2]); + } + offset_vec = g_origin[RIGHT] + g_origin[RIGHT + 1]; + normal = Vector3d(1, 0, 0); + rotation = Matrix3d::Identity(); + for (int i = RIGHT + 1; i < BASE; i++) { + double angleRad = toRadians(simulator->rightArmJoints_[simple][i - RIGHT - 1]); + rotation = AngleAxisd(angleRad, rotation * g_dir[i]) * rotation; + new_normal = rotation * normal; + InitArmSinglePolyhedron(simulator, i, &(*armPolyhedrons)[i], + offset_vec, + g_offset[i], + rotation); + simulator->addedOBBs_[simple][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[i], + simulator->collision_structures_[i].dimensions[0], + simulator->collision_structures_[i].dimensions[1], + simulator->collision_structures_[i].dimensions[2]); + } + + /*for (int i = LEFT; i <= BASE; ++i) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Link %d polyhedron points:", i); + for (int j = 0; j < ARM_POLYHEDRONS_POINT; ++j) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%d: %.4f %.4f %.4f", j, + simulator->armPolyhedrons_[0][i][j].x(), + simulator->armPolyhedrons_[0][i][j].y(), + simulator->armPolyhedrons_[0][i][j].z()); + } + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "---------------------"); + } + for (int i = LEFT; i <= BASE; i++) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "OBB: center(%.4f, %.4f, %.4f), axis1(%.4f, %.4f, %.4f), axis2(%.4f, %.4f, %.4f), axis3(%.4f, %.4f, %.4f), " + "half_length(%.4f, %.4f, %.4f)", + simulator->addedOBBs_[simple][i].center.x(), + simulator->addedOBBs_[simple][i].center.y(), + simulator->addedOBBs_[simple][i].center.z(), + simulator->addedOBBs_[simple][i].axis[0].x(), + simulator->addedOBBs_[simple][i].axis[0].y(), + simulator->addedOBBs_[simple][i].axis[0].z(), + simulator->addedOBBs_[simple][i].axis[1].x(), + simulator->addedOBBs_[simple][i].axis[1].y(), + simulator->addedOBBs_[simple][i].axis[1].z(), + simulator->addedOBBs_[simple][i].axis[2].x(), + simulator->addedOBBs_[simple][i].axis[2].y(), + simulator->addedOBBs_[simple][i].axis[2].z(), + simulator->addedOBBs_[simple][i].halfExtent[0], + simulator->addedOBBs_[simple][i].halfExtent[1], + simulator->addedOBBs_[simple][i].halfExtent[2]); + } + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "left joints: %.2f, %.2f, %.2f, %.2f, %.2f, %.2f", + simulator->leftArmJoints_[simple][0], + simulator->leftArmJoints_[simple][1], + simulator->leftArmJoints_[simple][2], + simulator->leftArmJoints_[simple][3], + simulator->leftArmJoints_[simple][4], + simulator->leftArmJoints_[simple][5]);*/ +} + +double truncate_to_4_decimal(double num) { + double int_part; // 存储整数部分 + double frac_part = std::modf(num, &int_part); // 分离小数部分 + + // 截断小数部分到前 4 位 + double truncated_frac = std::trunc(frac_part * 10000.0) * 0.0001; + + // 合并整数部分和截断后的小数部分 + return int_part + truncated_frac; +} + +static void ArmPoseChangeToOriFrame(float *pose, const JointInfo &joint) +{ + Vector3d offset; // 关节偏移 + Quaterniond rotation; // 关节旋转 + offset.x() = pose[0]; + offset.y() = pose[1]; + offset.z() = pose[2]; + rotation.x() = pose[3]; + rotation.y() = pose[4]; + rotation.z() = pose[5]; + rotation.w() = pose[6]; + rotation = joint.rotationAll * rotation; + offset = joint.rotationAll * offset + joint.offset; + pose[0] = truncate_to_4_decimal(offset.x()); + pose[1] = truncate_to_4_decimal(offset.y()); + pose[2] = truncate_to_4_decimal(offset.z()); + pose[3] = truncate_to_4_decimal(rotation.x()); + pose[4] = truncate_to_4_decimal(rotation.y()); + pose[5] = truncate_to_4_decimal(rotation.z()); + pose[6] = truncate_to_4_decimal(rotation.w()); +} + +static void OriFrameChangeToArmPose(float *pose, const JointInfo &joint) +{ + Vector3d offset; + Quaterniond rotation; + offset.x() = pose[0]; + offset.y() = pose[1]; + offset.z() = pose[2]; + rotation.x() = pose[3]; + rotation.y() = pose[4]; + rotation.z() = pose[5]; + rotation.w() = pose[6]; + Quaterniond inv_rotation = joint.rotationAll.inverse(); + Vector3d inv_position = {offset.x() - joint.offset.x(), + offset.y() - joint.offset.y(), + offset.z() - joint.offset.z()}; + offset = inv_rotation * inv_position; + rotation = inv_rotation * rotation; + pose[0] = truncate_to_4_decimal(offset.x()); + pose[1] = truncate_to_4_decimal(offset.y()); + pose[2] = truncate_to_4_decimal(offset.z()); + pose[3] = truncate_to_4_decimal(rotation.x()); + pose[4] = truncate_to_4_decimal(rotation.y()); + pose[5] = truncate_to_4_decimal(rotation.z()); + pose[6] = truncate_to_4_decimal(rotation.w()); +} + +static void InitPointsFromBoundsAndRotation(JointInfo &joint, CollisionStructure& col_struct) +{ + std::vector now = { + Vector3d(col_struct.mesh_bounds[0], col_struct.mesh_bounds[2], col_struct.mesh_bounds[4]), + Vector3d(col_struct.mesh_bounds[0], col_struct.mesh_bounds[2], col_struct.mesh_bounds[5]), + Vector3d(col_struct.mesh_bounds[0], col_struct.mesh_bounds[3], col_struct.mesh_bounds[4]), + Vector3d(col_struct.mesh_bounds[0], col_struct.mesh_bounds[3], col_struct.mesh_bounds[5]), + Vector3d(col_struct.mesh_bounds[1], col_struct.mesh_bounds[2], col_struct.mesh_bounds[4]), + Vector3d(col_struct.mesh_bounds[1], col_struct.mesh_bounds[2], col_struct.mesh_bounds[5]), + Vector3d(col_struct.mesh_bounds[1], col_struct.mesh_bounds[3], col_struct.mesh_bounds[4]), + Vector3d(col_struct.mesh_bounds[1], col_struct.mesh_bounds[3], col_struct.mesh_bounds[5]) + }; + int leftBottom = -1, xIndex = 0, yIndex = 0, zIndex = 0; + double xMax = 0, yMax = 0, zMax = 0; + for (int i = 0; i < ARM_POLYHEDRONS_POINT; ++i) { + // printf ("ori %.4f, %.4f, %.4f", now[i].x, now[i].y, now[i].z); + } + for (int i = 0; i < ARM_POLYHEDRONS_POINT; ++i) { + now[i] = joint.rotationAll * now[i]; + // printf ("aft %.4f, %.4f, %.4f", now[i].x(), now[i].y(), now[i].z()); + if (leftBottom != -1) { + if (now[i].x() - now[leftBottom].x()<= 1e-2 && + now[i].y() - now[leftBottom].y()<= 1e-2 && + now[i].z() - now[leftBottom].z()<= 1e-2) { + leftBottom = i; + } + if (xMax <= now[i].x()) { + xMax = now[i].x(); + xIndex = i; + } + if (yMax <= now[i].y()) { + yMax = now[i].y(); + yIndex = i; + } + if (zMax <= now[i].z()) { + zMax = now[i].z(); + zIndex = i; + } + } else { + leftBottom = 0; + } + } + Vector3d leftBottomPoint = now[0]; + now[0] = now[leftBottom]; + now[leftBottom] = leftBottomPoint; + g_offset[joint.child_link] = now[0]; + for (int i = 0; i < ARM_POLYHEDRONS_POINT; ++i) { + col_struct.origin_points.push_back(now[i]); + } + col_struct.mesh_bounds = {now[0].x(), xMax, now[0].y(), yMax, now[0].z(), zMax}; + col_struct.dimensions[0] = xMax - now[0].x(); + col_struct.dimensions[1] = yMax - now[0].y(); + col_struct.dimensions[2] = zMax - now[0].z(); +} + +static bool GetMeshDimensions(const std::string& filename, CollisionStructure& col_struct) +{ + // 加载网格文件 + shapes::Mesh* mesh = shapes::createMeshFromResource(filename); + if (!mesh) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "无法加载网格文件: %s", filename.c_str()); + return false; + } + // 计算边界盒 + double min_x = mesh->vertices[0], max_x = mesh->vertices[0]; + double min_y = mesh->vertices[1], max_y = mesh->vertices[1]; + double min_z = mesh->vertices[2], max_z = mesh->vertices[2]; + int min_index_x = 0, min_index_y = 0, min_index_z = 0; + int max_index_x = 0, max_index_y = 0, max_index_z = 0; + + for (unsigned int i = 1; i < mesh->vertex_count; ++i) { + if (min_x > mesh->vertices[3*i]) { + min_x = mesh->vertices[3*i]; + min_index_x = 3*i; + } + if (min_y > mesh->vertices[3*i + 1]) { + min_y = mesh->vertices[3*i + 1]; + min_index_y = 3*i; + } + if (min_z > mesh->vertices[3*i + 2]) { + min_z = mesh->vertices[3*i + 2]; + min_index_z = 3*i; + } + if (max_x < mesh->vertices[3*i]) { + max_x = mesh->vertices[3*i]; + max_index_x = 3*i; + } + if (max_y < mesh->vertices[3*i + 1]) { + max_y = mesh->vertices[3*i + 1]; + max_index_y = 3*i; + } + if (max_z < mesh->vertices[3*i + 2]) { + max_z = mesh->vertices[3*i + 2]; + max_index_z = 3*i; + } + } + + // 存储原始边界盒 + col_struct.mesh_bounds = {min_x, max_x, min_y, max_y, min_z, max_z}; + + // 计算原始尺寸 + double size_x = max_x - min_x; + double size_y = max_y - min_y; + double size_z = max_z - min_z; + col_struct.dimensions = {size_x, size_y, size_z}; + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "网格文件: %s", filename.c_str()); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "顶点数量: %u, 三角形数量: %u 大小:(%.4f, %.4f, %.4f)", mesh->vertex_count, mesh->triangle_count, + col_struct.dimensions[0], col_struct.dimensions[1], col_struct.dimensions[2]); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "边界盒: x(%.4f, %.4f), y(%.4f, %.4f), z(%.4f, %.4f)", + min_x, max_x, min_y, max_y, min_z, max_z); + + // 释放网格资源 + delete mesh; + return true; +} + +// 加载网格并计算边界盒 +static bool loadMeshDimensions(const std::string& filename, JointInfo &joint, CollisionStructure& col_struct) +{ + // 加载网格文件 + shapes::Mesh* mesh = shapes::createMeshFromResource(filename); + if (!mesh) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "无法加载网格文件: %s", filename.c_str()); + return false; + } + // 计算边界盒 + double min_x = mesh->vertices[0], max_x = mesh->vertices[0]; + double min_y = mesh->vertices[1], max_y = mesh->vertices[1]; + double min_z = mesh->vertices[2], max_z = mesh->vertices[2]; + int min_index_x = 0, min_index_y = 0, min_index_z = 0; + int max_index_x = 0, max_index_y = 0, max_index_z = 0; + + for (unsigned int i = 1; i < mesh->vertex_count; ++i) { + if (min_x > mesh->vertices[3*i]) { + min_x = mesh->vertices[3*i]; + min_index_x = 3*i; + } + if (min_y > mesh->vertices[3*i + 1]) { + min_y = mesh->vertices[3*i + 1]; + min_index_y = 3*i; + } + if (min_z > mesh->vertices[3*i + 2]) { + min_z = mesh->vertices[3*i + 2]; + min_index_z = 3*i; + } + if (max_x < mesh->vertices[3*i]) { + max_x = mesh->vertices[3*i]; + max_index_x = 3*i; + } + if (max_y < mesh->vertices[3*i + 1]) { + max_y = mesh->vertices[3*i + 1]; + max_index_y = 3*i; + } + if (max_z < mesh->vertices[3*i + 2]) { + max_z = mesh->vertices[3*i + 2]; + max_index_z = 3*i; + } + } + + // 存储原始边界盒 + col_struct.mesh_bounds = {min_x, max_x, min_y, max_y, min_z, max_z}; + + // 计算原始尺寸 + double size_x = max_x - min_x; + double size_y = max_y - min_y; + double size_z = max_z - min_z; + col_struct.dimensions = {size_x, size_y, size_z}; + InitPointsFromBoundsAndRotation(joint, col_struct); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "网格文件: %s", filename.c_str()); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "顶点数量: %u, 三角形数量: %u 大小:(%.4f, %.4f, %.4f)", mesh->vertex_count, mesh->triangle_count, + col_struct.dimensions[0], col_struct.dimensions[1], col_struct.dimensions[2]); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "边界盒: x(%.4f, %.4f), y(%.4f, %.4f), z(%.4f, %.4f)", + min_x, max_x, min_y, max_y, min_z, max_z); + + // 释放网格资源 + delete mesh; + return true; +} + +static int InitCollisionStructure(urdf::Model &urdf_model, ArmSimulator *simulator, + std::vector &collision_structures_temp) +{ + for (const auto& link_pair : urdf_model.links_) { + const std::string& link_name = link_pair.first; + const urdf::LinkConstSharedPtr& link = link_pair.second; + + // 检查链接是否有碰撞元素 + if (link->collision) { + CollisionStructure col_struct; + col_struct.link_name = link_name; + + // 获取原点位置和姿态 + if (link->collision != NULL) { + col_struct.origin_xyz = { + link->collision->origin.position.x, + link->collision->origin.position.y, + link->collision->origin.position.z + }; + col_struct.origin_rpy = { + link->collision->origin.rotation.x, + link->collision->origin.rotation.y, + link->collision->origin.rotation.z + }; + } + bool valid = true; + // 获取几何形状和尺寸 + if (link->collision->geometry) { + switch (link->collision->geometry->type) { + case urdf::Geometry::BOX: { + col_struct.geometry_type = "box"; + auto box = static_cast(link->collision->geometry.get()); + col_struct.dimensions = {box->dim.x, box->dim.y, box->dim.z}; + break; + } + case urdf::Geometry::CYLINDER: { + col_struct.geometry_type = "cylinder"; + auto cylinder = static_cast(link->collision->geometry.get()); + col_struct.dimensions = {cylinder->radius, cylinder->length}; + break; + } + case urdf::Geometry::SPHERE: { + col_struct.geometry_type = "sphere"; + auto sphere = static_cast(link->collision->geometry.get()); + col_struct.dimensions = {sphere->radius}; + break; + } + case urdf::Geometry::MESH: { + col_struct.geometry_type = "mesh"; + auto mesh = static_cast(link->collision->geometry.get()); + // 存储STL文件路径(关键信息) + col_struct.mesh_filename = mesh->filename; // 需要在结构体中添加这个成员 + auto index = g_linkMap.find(link_name); + if (index == g_linkMap.end()) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "no link"); + valid = false; + break; + } + int key = 0; + if (index->second == LEFT || index->second == RIGHT) { + key = (BASE << 8) | index->second; + } else { + key = ((index->second - 1) << 8) | (index->second); + } + auto joint = simulator->jointMap_.find(key); + if (joint == simulator->jointMap_.end()) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "no joint"); + GetMeshDimensions(mesh->filename, col_struct); + break; + } + loadMeshDimensions(mesh->filename, joint->second, col_struct); + break; + } + default: + col_struct.geometry_type = "unknown"; + break; + } + } + if (valid) { + collision_structures_temp.push_back(col_struct); + } + } + } + return 0; +} + +static int UpdateJointInfo(int i, int parent, Quaterniond &rotation, std::map &jointMap) +{ + int key = (parent << 8) | (i % 256); + auto jointPair = jointMap.find(key); + if (jointPair == jointMap.end()) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "lose joint %d -> %d", parent, i); + return -1; + } + + Vector3d position = rotation * jointPair->second.offset; + g_origin[i] = position; + + rotation = rotation * jointPair->second.rotation; + jointPair->second.rotationAll = rotation; + Eigen::Vector3d axis = jointPair->second.axis; + g_dir[i] = rotation * axis; + return 0; +} + +static int InitJoint(urdf::Model &urdf_model, std::map &jointMap) +{ + for (const auto& joint_pair : urdf_model.joints_) { + JointInfo jointInfo; + // joint_pair是一个键值对: 键为关节名称,值为关节指针 + jointInfo.name = joint_pair.first; + urdf::JointConstSharedPtr joint = joint_pair.second; + + jointInfo.type = joint->type; + jointInfo.parent_link = -1; + jointInfo.child_link = -1; + auto link = g_linkMap.find(joint->parent_link_name); + if (link != g_linkMap.end()) { + jointInfo.parent_link = link->second; + } else { + continue; + } + link = g_linkMap.find(joint->child_link_name); + if (link != g_linkMap.end()) { + jointInfo.child_link = link->second; + } else { + continue; + } + jointInfo.offset = Vector3d(joint->parent_to_joint_origin_transform.position.x, + joint->parent_to_joint_origin_transform.position.y, + joint->parent_to_joint_origin_transform.position.z); + jointInfo.rotation = Quaterniond( + joint->parent_to_joint_origin_transform.rotation.w, + joint->parent_to_joint_origin_transform.rotation.x, + joint->parent_to_joint_origin_transform.rotation.y, + joint->parent_to_joint_origin_transform.rotation.z); + if (joint->limits != NULL) { + jointInfo.limit_lower = joint->limits->lower; + jointInfo.limit_upper = joint->limits->upper; + jointInfo.limit_v = joint->limits->velocity; + jointInfo.limit_e = joint->limits->effort; + } + jointInfo.angle = 0; + jointInfo.axis = Vector3d(joint->axis.x, joint->axis.y, joint->axis.z); + + int key = ((jointInfo.parent_link % 256) << 8) | (jointInfo.child_link % 256); + jointMap[key] = jointInfo; + } + Quaterniond rotation = Quaterniond::Identity(); + int result = UpdateJointInfo(LEFT, BASE, rotation, jointMap); + if (result != 0) return -1; + for (int i = LEFT + 1; i < RIGHT; ++i) { + result = UpdateJointInfo(i, i - 1, rotation, jointMap); + if (result != 0) return -1; + } + rotation = Quaterniond::Identity(); + result = UpdateJointInfo(RIGHT, BASE, rotation, jointMap); + if (result != 0) return -1; + for (int i = RIGHT + 1; i < BASE; ++i) { + result = UpdateJointInfo(i, i - 1, rotation, jointMap); + if (result != 0) return -1; + } + return 0; +} + +static int InitArmPolyhedrons(ArmSimulator *simulator, urdf::Model &urdf_model) +{ + std::vector collision_structures_temp; + InitJoint(urdf_model, simulator->jointMap_); + InitCollisionStructure(urdf_model, simulator, collision_structures_temp); + return RemakeCollisionStructureList(simulator, collision_structures_temp); +} + +ArmSimulator::ArmSimulator(std::string urdf_string, float *left_now_joints, float *right_now_joints, + KinematicsManager *leftTrajectory, KinematicsManager *rightTrajectory) + : leftTrajectory_(leftTrajectory), rightTrajectory_(rightTrajectory) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ArmSimulator: 初始化机械臂碰撞检测模块..."); + urdf::Model urdf_model; + simpleUpdateIndex_ = 0; + if (!urdf_model.initString(urdf_string)) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "无法解析URDF模型"); + return; + } + for (int i = 0; i < ARM_COLLISION_CHECK_SIMPLE_CNT; i++) { + for (int j = 0; j < USED_ARM_DOF; j++) { + leftArmJoints_[i][j] = left_now_joints[j]; + rightArmJoints_[i][j] = right_now_joints[j]; + } + } + + InitArmPolyhedrons(this, urdf_model); + InitArmPolyhedronsList(this); + UpdateArmPolyhedrons(this); +} + +ArmSimulator::ArmSimulator(std_msgs::msg::String::SharedPtr urdf_string_ptr, float *left_now_joints, float *right_now_joints, + KinematicsManager *leftTrajectory, KinematicsManager *rightTrajectory) + : leftTrajectory_(leftTrajectory), rightTrajectory_(rightTrajectory) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ArmSimulator: 初始化机械臂碰撞检测模块..."); + std::string urdf_string = urdf_string_ptr->data; + for (int i = 0; i < ARM_COLLISION_CHECK_SIMPLE_CNT; i++) { + for (int j = 0; j < USED_ARM_DOF; j++) { + leftArmJoints_[i][j] = left_now_joints[j]; + rightArmJoints_[i][j] = right_now_joints[j]; + } + } + + // 解析URDF模型 + urdf::Model urdf_model; + simpleUpdateIndex_ = 0; + if (!urdf_model.initString(urdf_string)) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "无法解析URDF模型"); + return; + } + + InitArmPolyhedrons(this, urdf_model); + InitArmPolyhedronsList(this); + UpdateArmPolyhedrons(this); +} + +ArmSimulator::~ArmSimulator() +{ +} + +static int CheckCollisionInner(std::vector *addedOBBs, std::vector *addedOBBsNext_) +{ + int result = SAFE; + for (int i = LEFT; i < RIGHT; ++i) { + for (int j = i + 1; j < ARM_POLYHEDRONS_CNT; ++j) { + if (!LinkCollisionDetecMatrix[i][j]) { + continue; + } + bool inCollision = gjk_interface::checkOBBCollision((*addedOBBsNext_)[i], (*addedOBBsNext_)[j]); + if (inCollision) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "dect left %d and %d collision b", i, j); + result |= LEFT_ARM_COLLISION; + } + inCollision = gjk_interface::checkOBBCollision((*addedOBBs)[i], (*addedOBBsNext_)[j]); + if (inCollision) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "dect left %d and %d collision c", i, j); + result |= LEFT_ARM_COLLISION; + } + } + } + for (int i = RIGHT; i < BASE; ++i) { + for (int j = i + 1; j < ARM_POLYHEDRONS_CNT; ++j) { + if (!LinkCollisionDetecMatrix[i][j]) { + continue; + } + bool inCollision = gjk_interface::checkOBBCollision((*addedOBBsNext_)[i], (*addedOBBsNext_)[j]); + if (inCollision) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "dect right %d and %d collision b", i, j); + result |= RIGHT_ARM_COLLISION; + } + inCollision = gjk_interface::checkOBBCollision((*addedOBBs)[i], (*addedOBBsNext_)[j]); + if (inCollision) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "dect right %d and %d collision c", i, j); + result |= RIGHT_ARM_COLLISION; + } + } + } + return result; +} + +int ArmSimulator::UpdateCollisionForNewGoal(int arm) +{ + if (arm >= ARM_ID_ERR) return -1; + int simple20 = (simpleUpdateIndex_ + 1) % ARM_COLLISION_CHECK_SIMPLE_CNT; + int simple40 = (simple20 + 1) % ARM_COLLISION_CHECK_SIMPLE_CNT; + std::vector *armPolyhedrons20 = &(armPolyhedrons_[simple20]); + std::vector *armPolyhedrons40 = &(armPolyhedrons_[simple40]); + if (armPolyhedrons20->size() != ARM_POLYHEDRONS_CNT || armPolyhedrons40->size() != ARM_POLYHEDRONS_CNT) return -1; + int startLinkIndex, endLinkIndex; + float *jointList20; + float *jointList40; + + if (arm == LEFT_ARM) { + leftTrajectory_->getAngleForStarting(leftArmJoints_[simple20]); + leftTrajectory_->getAngleForChecking(leftArmJoints_[simple40]); + startLinkIndex = LEFT; + endLinkIndex = RIGHT; + jointList20 = leftArmJoints_[simple20]; + jointList40 = leftArmJoints_[simple40]; + } else if (arm == RIGHT_ARM) { + rightTrajectory_->getAngleForStarting(rightArmJoints_[simple20]); + rightTrajectory_->getAngleForChecking(rightArmJoints_[simple40]); + startLinkIndex = RIGHT; + endLinkIndex = BASE; + jointList20 = rightArmJoints_[simple20]; + jointList40 = rightArmJoints_[simple40]; + } + + if (CheckJointsAngleLimit(jointList20) != 0 || CheckJointsAngleLimit(jointList40) != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "AngleDirectMove joints limit error."); + return ARM_AIM_CANNOT_REACH; + } + + Vector3d offset_vec = g_origin[startLinkIndex] + g_origin[startLinkIndex + 1]; + Matrix3d rotation = Matrix3d::Identity(); + for (int i = startLinkIndex + 1; i < endLinkIndex; i++) { + double angleRad = toRadians(jointList20[i - startLinkIndex - 1]); + rotation = AngleAxisd(angleRad, rotation * g_dir[i]) * rotation; + InitArmSinglePolyhedron(this, i, &(*armPolyhedrons20)[i], + offset_vec, + g_offset[i], + rotation); + addedOBBs_[simple20][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons20)[i], + collision_structures_[i].dimensions[0], + collision_structures_[i].dimensions[1], + collision_structures_[i].dimensions[2]); + } + std::vector *addedOBBsNext_ = &(addedOBBs_[simple20]); + std::vector *addedOBBs = &(addedOBBs_[simpleUpdateIndex_]); + int result = CheckCollisionInner(addedOBBs, addedOBBsNext_); + if (result != SAFE) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "UpdateCollisionForNewGoal: arm %d collision", arm); + return result; + } + + offset_vec = g_origin[startLinkIndex] + g_origin[startLinkIndex + 1]; + rotation = Matrix3d::Identity(); + for (int i = startLinkIndex + 1; i < endLinkIndex; i++) { + double angleRad = toRadians(jointList40[i - startLinkIndex - 1]); + rotation = AngleAxisd(angleRad, rotation * g_dir[i]) * rotation; + InitArmSinglePolyhedron(this, i, &(*armPolyhedrons40)[i], + offset_vec, + g_offset[i], + rotation); + addedOBBs_[simple40][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons40)[i], + collision_structures_[i].dimensions[0], + collision_structures_[i].dimensions[1], + collision_structures_[i].dimensions[2]); + } + addedOBBsNext_ = &(addedOBBs_[simple40]); + addedOBBs = &(addedOBBs_[simple20]); + result = CheckCollisionInner(addedOBBs, addedOBBsNext_); + if (result != SAFE) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "UpdateCollisionForNewGoal: arm %d collision", arm); + return result; + } + return 0; +} + +int ArmSimulator::CheckCollision() +{ + int result = UpdateJointAngles(this); + if (result != 0) { + return result; + } + UpdateArmPolyhedrons(this); + int nowIndex = (simpleUpdateIndex_ + ARM_COLLISION_CHECK_SIMPLE_CNT - 1) % ARM_COLLISION_CHECK_SIMPLE_CNT; + std::vector *addedOBBsNext_ = &(addedOBBs_[simpleUpdateIndex_]); + std::vector *addedOBBs = &(addedOBBs_[nowIndex]); + result = CheckCollisionInner(addedOBBs, addedOBBsNext_); + + if (result != SAFE) { + if (result & LEFT_ARM_COLLISION) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "CheckCollision: left next joint: %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, now: %.2f, %.2f, %.2f, %.2f, %.2f, %.2f", + leftArmJoints_[simpleUpdateIndex_][0], + leftArmJoints_[simpleUpdateIndex_][1], + leftArmJoints_[simpleUpdateIndex_][2], + leftArmJoints_[simpleUpdateIndex_][3], + leftArmJoints_[simpleUpdateIndex_][4], + leftArmJoints_[simpleUpdateIndex_][5], + leftArmJoints_[nowIndex][0], + leftArmJoints_[nowIndex][1], + leftArmJoints_[nowIndex][2], + leftArmJoints_[nowIndex][3], + leftArmJoints_[nowIndex][4], + leftArmJoints_[nowIndex][5]); + } + if (result & RIGHT_ARM_COLLISION) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "CheckCollision: right next joint: %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, now: %.2f, %.2f, %.2f, %.2f, %.2f, %.2f", + rightArmJoints_[simpleUpdateIndex_][0], + rightArmJoints_[simpleUpdateIndex_][1], + rightArmJoints_[simpleUpdateIndex_][2], + rightArmJoints_[simpleUpdateIndex_][3], + rightArmJoints_[simpleUpdateIndex_][4], + rightArmJoints_[simpleUpdateIndex_][5], + rightArmJoints_[nowIndex][0], + rightArmJoints_[nowIndex][1], + rightArmJoints_[nowIndex][2], + rightArmJoints_[nowIndex][3], + rightArmJoints_[nowIndex][4], + rightArmJoints_[nowIndex][5]); + } + + result = ARM_COLLISION; + } else { + simpleUpdateIndex_ = (simpleUpdateIndex_ + 1) % ARM_COLLISION_CHECK_SIMPLE_CNT; + } + + return result; +} + +int ArmSimulator::ChangeOriFrameToArmBasePose(float *pose, int arm) +{ + if (!pose || arm >= ARM_ID_ERR) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangePoseToArmFrame: invalid pose"); + return -1; + } + int key = 0; + if (arm == LEFT_ARM) { + key = (BASE << 8) | (LEFT); + } else { + key = (BASE << 8) | (RIGHT); + } + auto joint = jointMap_.find(key); + if (joint == jointMap_.end()) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangePoseToArmFrame: no joint"); + return -1; + } + OriFrameChangeToArmPose(pose,joint->second); + return 0; +} + +int ArmSimulator::GetFrameChange(float *pose, int arm, int64_t frameTime, JointInfo *jointInfo) +{ + if (!pose || arm >= ARM_ID_ERR) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangePoseToArmFrame: invalid pose"); + return -1; + } + int key = 0, parent = 0; + int result = 0; + float jointList[USED_ARM_DOF] = {0}; + if (arm == LEFT_ARM) { + parent = LEFT; + result = leftTrajectory_->getAngleFromTime(jointList, frameTime); + } else { + parent = RIGHT; + result = rightTrajectory_->getAngleFromTime(jointList, frameTime); + } + if (result != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangePoseToArmFrame: get joint fail"); + return -1; + } + Quaterniond start = Quaterniond::Identity(); + Quaterniond rotationAll = Quaterniond::Identity(); + Vector3d offset(0, 0, 0); // 关节偏移 + for (int i = 0; i < USED_ARM_DOF; ++i) { + key = (parent << 8) | (parent + 1); + auto joint = jointMap_.find(key); + if (joint == jointMap_.end()) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangePoseToArmFrame: no joint"); + return -1; + } + + double angleRad = toRadians(jointList[i]); + rotationAll = joint->second.rotation * rotationAll; + Quaterniond axis(AngleAxisd(angleRad, start * rotationAll * joint->second.axis)); + start = axis * start; + offset = offset + start * rotationAll * joint->second.offset; + // RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "offset: (%.4f, %.4f, %.4f)", offset.x(), offset.y(), offset.z()); + parent = parent + 1; + } + jointInfo->rotationAll = start; + jointInfo->offset = offset; + return 0; +} + +int ArmSimulator::ChangeArmBaseFrameToArmEndPose(float *pose, int arm, int64_t frameTime) +{ + JointInfo jointInfo; + int result = GetFrameChange(pose, arm, frameTime, &jointInfo); + if (result != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangeArmBaseFrameToArmEndPose: get frame change fail"); + return -1; + } + OriFrameChangeToArmPose(pose, jointInfo); + return 0; +} + +int ArmSimulator::ChangeArmEndPoseToArmBaseFrame(float *pose, int arm, int64_t frameTime) +{ + JointInfo jointInfo; + int result = GetFrameChange(pose, arm, frameTime, &jointInfo); + if (result != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangeArmEndPoseToArmBaseFrame: get frame change fail"); + return -1; + } + + ArmPoseChangeToOriFrame(pose, jointInfo); + return 0; +} + +int ArmSimulator::ChangeArmBasePoseToOriFrame(float *pose, int arm) +{ + if (!pose || arm >= ARM_ID_ERR) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangePoseToOriFrame: invalid pose"); + return -1; + } + int key = 0; + if (arm == LEFT_ARM) { + key = (BASE << 8) | (LEFT); + } else { + key = (BASE << 8) | (RIGHT); + } + auto joint = jointMap_.find(key); + if (joint == jointMap_.end()) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ChangePoseToOriFrame: no joint"); + return -1; + } + ArmPoseChangeToOriFrame(pose, joint->second); + return 0; +} + +int ArmSimulator::AddPolyhedron(int id, const Polyhedron& poly) +{ + if (addedPolyhedrons_.find(id) != addedPolyhedrons_.end()) { + return -1; // 已存在相同ID的多面体 + } + addedPolyhedrons_[id] = poly; + return 0; // 成功添加 +} + +int ArmSimulator::RemovePolyhedron(int id) +{ + auto it = addedPolyhedrons_.find(id); + if (it != addedPolyhedrons_.end()) { + addedPolyhedrons_.erase(it); + return 0; // 成功移除 + } + return -1; // 未找到对应ID的多面体 +} + +int ArmSimulator::CheckJointsAngleLimit(float *joints) +{ + for (int i = 0; i < USED_ARM_DOF; ++i) { + auto joint = jointMap_.find(((i) << 8) | (i + 1)); + if (joint != jointMap_.end()) { + float angle = toRadians(joints[i]); + if (angle < joint->second.limit_lower || angle > joint->second.limit_upper) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), + "CheckJointsAngleLimit: joint out of limit [%.4f, %.4f], current: %.4f(%.2f)", + joint->second.limit_lower, joint->second.limit_upper, angle, joints[i]); + return ARM_AIM_CANNOT_REACH; + } + } else { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "CheckJointsAngleLimit: no joint"); + return ARM_AIM_CANNOT_REACH; + } + } + return 0; +} diff --git a/rm_arm_control/simulator/rm_driver_kinematics.cpp b/rm_arm_control/simulator/rm_driver_kinematics.cpp new file mode 100644 index 0000000..432fab0 --- /dev/null +++ b/rm_arm_control/simulator/rm_driver_kinematics.cpp @@ -0,0 +1,379 @@ +#include "arm_driver.hpp" +#include "rm_driver_kinematics.hpp" +#include +#include + +using namespace Eigen; + +#define MIN_MOVING_TIME_STEP 80 + +RmArmDriverAndKinematics::RmArmDriverAndKinematics() +{ + rmService_ = nullptr; + initFlag_ = RM_DRIVER_KINEMATICS_UNINIT; +} + +RmArmDriverAndKinematics::~RmArmDriverAndKinematics() +{ + if (rmService_ != nullptr) { + rmService_->rm_destroy(); + delete rmService_; + } +} + +RmArmDriverAndKinematics::RmArmStatusCallbackFun RmArmDriverAndKinematics::armStatusCallback_ = nullptr; +RmArmDriverAndKinematics::ApiLogFunc RmArmDriverAndKinematics::customApiLog_ = nullptr; +rm_robot_handle *RmArmDriverAndKinematics::leftRobotHandle_; +rm_robot_handle *RmArmDriverAndKinematics::rightRobotHandle_; +RM_Service *RmArmDriverAndKinematics::rmService_ = nullptr; + +void RmArmDriverAndKinematics::CallbackRmRealtimeArmJointState(rm_realtime_arm_joint_state_t data) +{ + ArmStatusCallbackData callbackData; + callbackData.errCode = 0; + if (armStatusCallback_ == nullptr) { + return; + } + if (strcmp(data.arm_ip, LEFT_ARM_IP_ADDRESS) == 0) { + callbackData.armId = LEFT_ARM; + } + else if (strcmp(data.arm_ip, RIGHT_ARM_IP_ADDRESS) == 0) { + callbackData.armId = RIGHT_ARM; + } else { + api_log("Unknown arm ip: %s", data.arm_ip); + return; + } + + callbackData.errCode = data.errCode; + for (size_t i = 0; i < USED_ARM_DOF; i++) { + callbackData.jointCurrent[i] = data.joint_status.joint_current[i]; + callbackData.jointEnFlag[i] = data.joint_status.joint_en_flag[i]; + callbackData.jointAngle[i] = data.joint_status.joint_position[i]; + callbackData.jointSpeed[i] = data.joint_status.joint_speed[i]; + callbackData.jointTemp[i] = data.joint_status.joint_temperature[i]; + callbackData.jointVoltage[i] = data.joint_status.joint_voltage[i]; + callbackData.jointTorque[i] = data.force_sensor.force[i]; + callbackData.jointErrCode[i] = data.joint_status.joint_err_code[i]; + } + + armStatusCallback_(&callbackData); +} + +void RmArmDriverAndKinematics::api_log(const char* format, ...) +{ + va_list args; + va_start(args, format);// 初始化可变参数列表 + customApiLog_(format, args);// 调用函数指针,传递 va_list + va_end(args);// 清理可变参数列表 +} + +int RmArmDriverAndKinematics::InitHandle(rm_robot_handle **robotHandle_, const char *robot_ip_address, int robot_port, rm_realtime_push_config_t *config) +{ + *robotHandle_ = rmService_->rm_create_robot_arm(robot_ip_address, robot_port); + if (*robotHandle_ == NULL) { + api_log("Failed to create arm(%s) handle.", robot_ip_address); + return UNKNOWN_ERR; + } + if ((*robotHandle_)->id <= 0) { + api_log("Failed to create arm(%s) handle. %d", robot_ip_address, (*robotHandle_)->id); + return UNKNOWN_ERR; + } + + int result = rmService_-> rm_set_realtime_push(*robotHandle_, *config); + if (result != 0) { + api_log("Failed to set realtime push for arm(%s).", robot_ip_address); + return UNKNOWN_ERR; + } + result = rm_set_arm_max_line_speed(*robotHandle_, 0.01f); + if (result != 0) { + api_log("Failed to set max line speed for arm(%s).", robot_ip_address); + return UNKNOWN_ERR; + } + + rm_robot_info_t robot_info; + int info_result = rmService_->rm_get_robot_info(*robotHandle_, &robot_info); + if (info_result != 0) { + api_log("Failed to get robot info(%s)", robot_ip_address); + return UNKNOWN_ERR; + } + int dof = robot_info.arm_dof; + if (dof != USED_ARM_DOF) { + api_log("Invalid degree of freedom(%s)", robot_ip_address); + return UNKNOWN_ERR; + } + return 0; +} + +int RmArmDriverAndKinematics::Init() +{ + if (initFlag_ == RM_DRIVER_KINEMATICS_INIT_OK) { + return OK; + } + if (customApiLog_ == nullptr || armStatusCallback_ == nullptr) { + return UNKNOWN_ERR; + } + rmService_ = new RM_Service(); + if (rmService_ == nullptr) { + return UNKNOWN_ERR; + } + int result = rmService_->rm_init(RM_TRIPLE_MODE_E); + if (result != 0) { + rmService_->rm_destroy(); + delete rmService_; + return UNKNOWN_ERR; + } + + rmService_->rm_set_log_call_back(customApiLog_, 3); + rmService_->rm_realtime_arm_state_call_back(CallbackRmRealtimeArmJointState); + + int robot_port = ARM_IP_PORT; + rm_realtime_push_config_t config = {20, true, 8089, 0, "192.168.2.3"}; + result = InitHandle(&leftRobotHandle_, LEFT_ARM_IP_ADDRESS, robot_port, &config); + if (result != 0) { + rmService_->rm_destroy(); + delete rmService_; + return UNKNOWN_ERR; + } + config = {20, true, 8089, 0, "192.168.2.19"}; + result = InitHandle(&rightRobotHandle_, RIGHT_ARM_IP_ADDRESS, robot_port, &config); + if (result != 0) { + rmService_->rm_destroy(); + delete rmService_; + return UNKNOWN_ERR; + } + + rm_robot_arm_model_e Mode = RM_MODEL_RM_65_E; + rm_force_type_e Type = RM_MODEL_RM_B_E; + rm_algo_init_sys_data(Mode, Type); + + initFlag_ = RM_DRIVER_KINEMATICS_INIT_OK; + return OK; +} + +void RmArmDriverAndKinematics::getAngleForCheckingInner(NodataTrajectory *traj, int timeStep, float *aimAngles) +{ + return; +} + +void RmArmDriverAndKinematics::getAngleForCheckingOffset(NodataTrajectory *traj, int timeStepOffset, float *aimAngles) +{ + return; +} + +int RmArmDriverAndKinematics::ArmMove(const float points[USED_ARM_DOF], int armId) +{ + return OK; +} + +int RmArmDriverAndKinematics::updateTrajectory(NodataTrajectory *trajectory, float *aimAngles) +{ + if (trajectory->goalType == GOAL_TYPE_MOVING){ + ++trajectory->currentStep; + if (trajectory->currentStep >= MIN_MOVING_TIME_STEP) { + return TRAJECTORY_COMPLETE; + } + } else { + rm_robot_handle *robotHandle = nullptr; + if (trajectory->armId == LEFT_ARM) { + robotHandle = leftRobotHandle_; + } else if (trajectory->armId == RIGHT_ARM) { + robotHandle = rightRobotHandle_; + } else { + api_log("Invalid armId: %d", trajectory->armId); + return UNKNOWN_ERR; + } + int result = 0; + if (trajectory->goalType == GOAL_TYPE_POSE_STEPPING) { + if (trajectory->end[POSE_POSITION_X] != 0.0f) { + result |= rm_set_pos_step(robotHandle, RM_X_DIR_E, trajectory->end[POSE_POSITION_X], 40, 0); + } + if (trajectory->end[POSE_POSITION_Y] != 0.0f) { + result |= rm_set_pos_step(robotHandle, RM_Y_DIR_E, trajectory->end[POSE_POSITION_Y], 40, 0); + } + if (trajectory->end[POSE_POSITION_Z] != 0.0f) { + result |= rm_set_pos_step(robotHandle, RM_Z_DIR_E, trajectory->end[POSE_POSITION_Z], 40, 0); + } + } else if (trajectory->goalType == GOAL_TYPE_STEPPING) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + result |= rm_set_joint_step(robotHandle, i + 1, trajectory->end[i], 5, 0); + } + } + + if (result != 0) { + return ARM_AIM_CANNOT_REACH; + } + } + return TRAJECTORY_ONGOING; +} + +int RmArmDriverAndKinematics::computeMovingTrajectory(NodataTrajectory *newTrajectory, const float *start, const float *end, int armId) +{ + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->start[i] = start[i]; + newTrajectory->end[i] = end[i]; + } + newTrajectory->runState = RM_KINEMATICS_STATUS_INIT; + newTrajectory->goalType = GOAL_TYPE_MOVING; + newTrajectory->armId = armId; + newTrajectory->currentStep = 0; + + rm_robot_handle *robotHandle = nullptr; + if (armId == LEFT_ARM) { + robotHandle = leftRobotHandle_; + } else if (armId == RIGHT_ARM) { + robotHandle = rightRobotHandle_; + } else { + api_log("Invalid armId: %d", armId); + return UNKNOWN_ERR; + } + float joints[ARM_DOF]; + for (int i = 0; i < USED_ARM_DOF; ++i) { + joints[i] = end[i]; + } + rm_movej(robotHandle, joints, 5, 1, 0, 0); + return 0; +} + +int RmArmDriverAndKinematics::computeSteppingTrajectory(NodataTrajectory *newTrajectory, const float *start, const float *speed, int armId) +{ + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->start[i] = start[i]; + newTrajectory->end[i] = speed[i]; + } + newTrajectory->runState = RM_KINEMATICS_STATUS_INIT; + newTrajectory->goalType = GOAL_TYPE_STEPPING; + newTrajectory->armId = armId; + newTrajectory->currentStep = 0; + rm_robot_handle *robotHandle = nullptr; + if (armId == LEFT_ARM) { + robotHandle = leftRobotHandle_; + } else if (armId == RIGHT_ARM) { + robotHandle = rightRobotHandle_; + } else { + api_log("Invalid armId: %d", armId); + return UNKNOWN_ERR; + } + float joints[ARM_DOF]; + int result = 0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + result |= rm_set_joint_step(robotHandle, i + 1, speed[i], 5, 0); + } + return result; +} + +int RmArmDriverAndKinematics::computePoseSteppingTrajectory(NodataTrajectory *newTrajectory, const float *start, const float *pose, int armId) +{ + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->start[i] = start[i]; + newTrajectory->end[i] = pose[i]; + } + newTrajectory->runState = RM_KINEMATICS_STATUS_INIT; + newTrajectory->goalType = GOAL_TYPE_POSE_STEPPING; + newTrajectory->armId = armId; + newTrajectory->currentStep = 0; + rm_robot_handle *robotHandle = nullptr; + if (armId == LEFT_ARM) { + robotHandle = leftRobotHandle_; + } else if (armId == RIGHT_ARM) { + robotHandle = rightRobotHandle_; + } else { + api_log("Invalid armId: %d", armId); + return UNKNOWN_ERR; + } + + int result = 0; + if (pose[POSE_POSITION_X] != 0.0f) { + result |= rm_set_pos_step(robotHandle, RM_X_DIR_E, pose[POSE_POSITION_X], 40, 0); + } + if (pose[POSE_POSITION_Y] != 0.0f) { + result |= rm_set_pos_step(robotHandle, RM_Y_DIR_E, pose[POSE_POSITION_Y], 40, 0); + } + if (pose[POSE_POSITION_Z] != 0.0f) { + result |= rm_set_pos_step(robotHandle, RM_Z_DIR_E, pose[POSE_POSITION_Z], 40, 0); + } + + return result; +} + +void RmArmDriverAndKinematics::stopTrajectory(NodataTrajectory *traj) +{ + rm_robot_handle *robotHandle = nullptr; + if (traj->armId == LEFT_ARM) { + robotHandle = leftRobotHandle_; + } else if (traj->armId == RIGHT_ARM) { + robotHandle = rightRobotHandle_; + } else { + api_log("Invalid armId: %d", traj->armId); + return; + } + if (traj->goalType == GOAL_TYPE_MOVING) { + rm_set_arm_stop(robotHandle); + return; + } + else if (traj->goalType == GOAL_TYPE_STEPPING) { + traj->goalType = GOAL_TYPE_MOVING; + traj->currentStep = MIN_MOVING_TIME_STEP; + return; + } + else if (traj->goalType == GOAL_TYPE_POSE_STEPPING) { + traj->goalType = GOAL_TYPE_MOVING; + traj->currentStep = MIN_MOVING_TIME_STEP; + return; + } +} + +int RmArmDriverAndKinematics::continuePoseSteppingTrajectory(NodataTrajectory *newTrajectory, const float *nowAngles, const float *direct) +{ + return ARM_GOAL_CANCELLED; +} + +int RmArmDriverAndKinematics::ForwardKinematics(float *jointAngles, float *endEffectorPose) +{ + if (!rmService_) + { + return UNKNOWN_ERR; // Error: RM_Service not initialized + } + + // Call the RM_Service's ForwardKinematics method + rm_pose_t pose = rmService_->rm_algo_forward_kinematics(NULL, jointAngles); + endEffectorPose[POSE_POSITION_X] = pose.position.x; + endEffectorPose[POSE_POSITION_Y] = pose.position.y; + endEffectorPose[POSE_POSITION_Z] = pose.position.z; + endEffectorPose[POSE_QUATERNION_X] = pose.quaternion.x; + endEffectorPose[POSE_QUATERNION_Y] = pose.quaternion.y; + endEffectorPose[POSE_QUATERNION_Z] = pose.quaternion.z; + endEffectorPose[POSE_QUATERNION_W] = pose.quaternion.w; + return 0; +} + +int RmArmDriverAndKinematics::InverseKinematics(const float *endEffectorPose, float *jointAngles) +{ + if (!rmService_) + { + return UNKNOWN_ERR; // Error: RM_Service not initialized + } + + float nowJoints_[ARM_DOF] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; + for (int i = 0; i < USED_ARM_DOF; i++) { + nowJoints_[i] = jointAngles[i]; + } + rm_inverse_kinematics_params_t inverse_params; + memcpy(inverse_params.q_in, nowJoints_, sizeof(nowJoints_)); + inverse_params.q_pose.position.x = endEffectorPose[POSE_POSITION_X]; + inverse_params.q_pose.position.y = endEffectorPose[POSE_POSITION_Y]; + inverse_params.q_pose.position.z = endEffectorPose[POSE_POSITION_Z]; + inverse_params.q_pose.quaternion.x = endEffectorPose[POSE_QUATERNION_X]; + inverse_params.q_pose.quaternion.y = endEffectorPose[POSE_QUATERNION_Y]; + inverse_params.q_pose.quaternion.z = endEffectorPose[POSE_QUATERNION_Z]; + inverse_params.q_pose.quaternion.w = endEffectorPose[POSE_QUATERNION_W]; + inverse_params.flag = 0; + + int result = rmService_->rm_algo_inverse_kinematics(NULL, inverse_params, nowJoints_); + if (result != 0){ + return ARM_AIM_CANNOT_REACH; // Inverse kinematics failed + } + memcpy(jointAngles, nowJoints_, sizeof(float) * USED_ARM_DOF); + return 0; +} + + diff --git a/rm_arm_control/simulator/trapezoidal_trajectory_kinematics.cpp b/rm_arm_control/simulator/trapezoidal_trajectory_kinematics.cpp new file mode 100644 index 0000000..089f1eb --- /dev/null +++ b/rm_arm_control/simulator/trapezoidal_trajectory_kinematics.cpp @@ -0,0 +1,344 @@ +#include +#include "arm_define.h" +#include "trapezoidal_trajectory_kinematics.hpp" +#include +#include + +extern double truncate_to_4_decimal(double num); + +TrapezoidalTrajectoryKinematics::TrapezoidalTrajectoryKinematics(RM_Service *rmService) + : max_velocity_(0.4), max_acceleration_(0.1), rmService_(rmService) +{ + max_accelerate_time_ = 4; + max_accelerate_angle_ = max_velocity_ * max_accelerate_time_; + min_angle_for_pose_stepping_max_speed_ = ARM_FOLLOWING_CHECKING_STEP * max_velocity_ * 2; + + rm_robot_arm_model_e Mode = RM_MODEL_RM_65_E; + rm_force_type_e Type = RM_MODEL_RM_B_E; + rm_algo_init_sys_data(Mode, Type); +} + +TrapezoidalTrajectoryKinematics::TrapezoidalTrajectoryKinematics() + : max_velocity_(0.4), max_acceleration_(0.1), rmService_(nullptr) +{ + max_accelerate_time_ = 4; + max_accelerate_angle_ = max_velocity_ * max_accelerate_time_; + min_angle_for_pose_stepping_max_speed_ = ARM_FOLLOWING_CHECKING_STEP * max_velocity_ * 2; + + rmService_ = new RM_Service(); + int result = rmService_->rm_init(RM_TRIPLE_MODE_E); + if (result != 0) { + throw std::runtime_error("Failed to init rm."); + return; + } + rm_robot_arm_model_e Mode = RM_MODEL_RM_65_E; + rm_force_type_e Type = RM_MODEL_RM_B_E; + rm_algo_init_sys_data(Mode, Type); +} + +TrapezoidalTrajectoryKinematics::~TrapezoidalTrajectoryKinematics() { + delete rmService_; +} + +void TrapezoidalTrajectoryKinematics::getAngleForCheckingInner(TrapezoidalTrajectory *traj, int timeStep, float *aimAngles) +{ + if (timeStep >= traj->accelerate_time_step * 2 + traj->uniform_time_step + && traj->uniform_time_step != STEPPING_UNIFORM_TIME_STAMP) { // 分支预判优化 + for (int i = 0; i < USED_ARM_DOF; ++i) { + aimAngles[i] = traj->endAngles[i]; + } + return; + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + if (timeStep < traj->accelerate_time_step) { + aimAngles[i] = traj->startAngles[i] + 0.5 * traj->now_acceleration[i] * (timeStep + 1) * timeStep; + } else if (traj->uniform_time_step == STEPPING_UNIFORM_TIME_STAMP){ + aimAngles[i] = traj->startAngles[i] + 0.5 * traj->now_acceleration[i] * (traj->accelerate_time_step + 1) * (traj->accelerate_time_step); + aimAngles[i] += traj->aim_velocity[i] * (timeStep - traj->accelerate_time_step); + }else if (timeStep < traj->accelerate_time_step + traj->uniform_time_step) { + aimAngles[i] = traj->endAngles[i] - 0.5 * traj->now_acceleration[i] * (traj->accelerate_time_step - 1) * (traj->accelerate_time_step); + aimAngles[i] -= traj->aim_velocity[i] * (traj->uniform_time_step - (timeStep - traj->accelerate_time_step)); + } else if (timeStep <= 2 * traj->accelerate_time_step + traj->uniform_time_step) { + int decelerate_time_step = 2 * traj->accelerate_time_step + traj->uniform_time_step - timeStep; + aimAngles[i] = traj->endAngles[i] - 0.5 * traj->now_acceleration[i] * (decelerate_time_step - 1) * decelerate_time_step; + } + } +} + +void TrapezoidalTrajectoryKinematics::getAngleForCheckingOffset(TrapezoidalTrajectory *traj, int timeStepOffset, float *aimAngles) +{ + int timeStep = traj->current_time_step + timeStepOffset; + getAngleForCheckingInner(traj, timeStep, aimAngles); +} + +int TrapezoidalTrajectoryKinematics::updateTrajectory(TrapezoidalTrajectory *trajectory, float *aimAngles) +{ + trajectory->current_time_step++; + if (trajectory->goalType == GOAL_TYPE_POSE_STEPPING && trajectory->current_time_step >= trajectory->accelerate_time_step + trajectory->uniform_time_step) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + int decelerate_time_step = trajectory->accelerate_time_step; + aimAngles[i] = trajectory->endAngles[i] - 0.5 * trajectory->now_acceleration[i] * (decelerate_time_step + 1) * decelerate_time_step; + } + return TRAJECTORY_COMPLETE; + } else if (trajectory->current_time_step >= trajectory->accelerate_time_step * 2 + trajectory->uniform_time_step + && trajectory->uniform_time_step != STEPPING_UNIFORM_TIME_STAMP) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + aimAngles[i] = trajectory->endAngles[i]; + } + return TRAJECTORY_COMPLETE; + } + getAngleForCheckingInner(trajectory, trajectory->current_time_step, aimAngles); + return TRAJECTORY_ONGOING; +} + +int TrapezoidalTrajectoryKinematics::computeMovingTrajectory(TrapezoidalTrajectory *newTrajectory, const float *start, const float *end, int armId) +{ + newTrajectory->goalType = GOAL_TYPE_MOVING; + newTrajectory->current_time_step = 0; + float max_angle = 0.0; + float angle_diff[USED_ARM_DOF]; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->startAngles[i] = start[i]; + newTrajectory->endAngles[i] = end[i]; + angle_diff[i] = end[i] - start[i]; + float abs_diff = fabs(angle_diff[i]); + if (abs_diff > max_angle) { + max_angle = abs_diff; + } + } + if (max_angle < 0.01) { + newTrajectory->accelerate_time_step = 0; + newTrajectory->uniform_time_step = 0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->aim_velocity[i] = 0; + newTrajectory->now_acceleration[i] = 0; + newTrajectory->endAngles[i] = start[i]; + } + return OK; + } + float aim_velocity = max_velocity_; + if (max_angle < max_accelerate_angle_) { + newTrajectory->accelerate_time_step = static_cast(sqrt(max_angle / max_acceleration_)) + 1; + aim_velocity = max_angle / newTrajectory->accelerate_time_step; + newTrajectory->uniform_time_step = 0; + } else { + newTrajectory->accelerate_time_step = max_accelerate_time_; + newTrajectory->uniform_time_step = static_cast((max_angle - max_accelerate_angle_) / max_velocity_); + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->aim_velocity[i] = aim_velocity * angle_diff[i] / max_angle; + newTrajectory->now_acceleration[i] = newTrajectory->aim_velocity[i] / newTrajectory->accelerate_time_step; + } + return OK; +} + +int TrapezoidalTrajectoryKinematics::computeSteppingTrajectory(TrapezoidalTrajectory *newTrajectory, const float *start, const float *speed, int armId) +{ + newTrajectory->goalType = GOAL_TYPE_STEPPING; + newTrajectory->current_time_step = 0; + float maxSpeed = 0.0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->startAngles[i] = start[i]; + if (fabs(speed[i]) > max_velocity_) { + newTrajectory->aim_velocity[i] = (speed[i] > 0 ? 1 : -1) * max_velocity_; + } else { + newTrajectory->aim_velocity[i] = speed[i]; + } + if (fabs(newTrajectory->aim_velocity[i]) > maxSpeed) { + maxSpeed = fabs(newTrajectory->aim_velocity[i]); + } + } + newTrajectory->uniform_time_step = -1; + newTrajectory->accelerate_time_step = static_cast(maxSpeed / max_acceleration_) + 1; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->now_acceleration[i] = newTrajectory->aim_velocity[i] / newTrajectory->accelerate_time_step; + newTrajectory->endAngles[i] = 0; + } + return OK; +} + +int TrapezoidalTrajectoryKinematics::computePoseSteppingTrajectory(TrapezoidalTrajectory *newTrajectory, const float *start, const float *pose, int armId) +{ + newTrajectory->goalType = GOAL_TYPE_POSE_STEPPING; + newTrajectory->current_time_step = 0; + float end[ARM_DOF] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; + for (int i = 0; i < USED_ARM_DOF; i++) { + end[i] = start[i]; + } + int result = PoseSteppingFromNowAnglesAndDirectPose(end, pose); + if (result != 0){ + return ARM_AIM_CANNOT_REACH; // Inverse kinematics failed + } + + float max_angle = 0.0; + float angle_diff[USED_ARM_DOF]; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->startAngles[i] = start[i]; + newTrajectory->endAngles[i] = end[i]; + angle_diff[i] = end[i] - start[i]; + float abs_diff = fabs(angle_diff[i]); + if (abs_diff > max_angle) { + max_angle = abs_diff; + } + } + if (max_angle < 0.01) { + newTrajectory->accelerate_time_step = 0; + newTrajectory->uniform_time_step = 0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->aim_velocity[i] = 0; + newTrajectory->now_acceleration[i] = 0; + newTrajectory->endAngles[i] = start[i]; + } + return OK; + } + float aim_velocity = max_velocity_; + newTrajectory->accelerate_time_step = max_accelerate_time_; + if (max_angle < min_angle_for_pose_stepping_max_speed_) { + aim_velocity = max_angle / (ARM_FOLLOWING_CHECKING_STEP * 2); + newTrajectory->uniform_time_step = ARM_FOLLOWING_CHECKING_STEP * 2 - max_accelerate_time_; + } else { + newTrajectory->uniform_time_step = static_cast((max_angle - (max_accelerate_angle_ - 1) * 0.5) / max_velocity_); + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->aim_velocity[i] = aim_velocity * angle_diff[i] / max_angle; + newTrajectory->now_acceleration[i] = newTrajectory->aim_velocity[i] / max_accelerate_time_; + } + return OK; +} + +void TrapezoidalTrajectoryKinematics::stopTrajectory(TrapezoidalTrajectory *traj) +{ + int formerPoseSteppingUniformTimeStep = traj->uniform_time_step; + if (traj->current_time_step < traj->accelerate_time_step) { + traj->accelerate_time_step = traj->current_time_step; + traj->uniform_time_step = 0; + } else if (traj->uniform_time_step == STEPPING_UNIFORM_TIME_STAMP || + traj->current_time_step < traj->accelerate_time_step + traj->uniform_time_step) { + traj->uniform_time_step = traj->current_time_step - traj->accelerate_time_step; + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + if (traj->goalType == GOAL_TYPE_POSE_STEPPING) { + traj->now_acceleration[i] = traj->aim_velocity[i] / traj->accelerate_time_step; + traj->endAngles[i] = traj->endAngles[i] + - traj->aim_velocity[i] * (formerPoseSteppingUniformTimeStep - traj->uniform_time_step); + } else if (traj->current_time_step <= traj->accelerate_time_step + traj->uniform_time_step) { + traj->endAngles[i] = traj->startAngles[i] + traj->aim_velocity[i] * (traj->uniform_time_step + traj->accelerate_time_step); + } + } + if (traj->goalType == GOAL_TYPE_POSE_STEPPING) { + traj->goalType = GOAL_TYPE_MOVING; + } +} + +int TrapezoidalTrajectoryKinematics::PoseSteppingFromNowAnglesAndDirectPose(float *nowAngles, const float *direct) +{ + rm_pose_t pose = rmService_->rm_algo_forward_kinematics(NULL, nowAngles); + + rm_inverse_kinematics_params_t inverse_params; + memcpy(inverse_params.q_in, nowAngles, ARM_DOF * sizeof(float)); + inverse_params.q_pose.position.x = direct[POSE_POSITION_X] + truncate_to_4_decimal(pose.position.x); + inverse_params.q_pose.position.y = direct[POSE_POSITION_Y] + truncate_to_4_decimal(pose.position.y); + inverse_params.q_pose.position.z = direct[POSE_POSITION_Z] + truncate_to_4_decimal(pose.position.z); + inverse_params.q_pose.quaternion.x = direct[POSE_QUATERNION_X] + truncate_to_4_decimal(pose.quaternion.x); + inverse_params.q_pose.quaternion.y = direct[POSE_QUATERNION_Y] + truncate_to_4_decimal(pose.quaternion.y); + inverse_params.q_pose.quaternion.z = direct[POSE_QUATERNION_Z] + truncate_to_4_decimal(pose.quaternion.z); + inverse_params.q_pose.quaternion.w = direct[POSE_QUATERNION_W] + truncate_to_4_decimal(pose.quaternion.w); + inverse_params.flag = 0; + + int result = rmService_->rm_algo_inverse_kinematics(NULL, inverse_params, nowAngles); + if (result != 0){ + return ARM_AIM_CANNOT_REACH; // Inverse kinematics failed + } + return 0; +} + +int TrapezoidalTrajectoryKinematics::continuePoseSteppingTrajectory(TrapezoidalTrajectory *newTrajectory, const float *nowAngles, const float *direct) +{ + if (!newTrajectory || newTrajectory->goalType != GOAL_TYPE_POSE_STEPPING) { + return ARM_GOAL_CANCELLED; + } + float newJoints[ARM_DOF] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; + for (int i = 0; i < USED_ARM_DOF; i++) { + newJoints[i] = newTrajectory->endAngles[i]; + } + int result = PoseSteppingFromNowAnglesAndDirectPose(newJoints, direct); + if (result != 0){ + return ARM_AIM_CANNOT_REACH; // Inverse kinematics failed + } + + float angle_diff[USED_ARM_DOF]; + float max_angle = 0.0; + float max_velocity = 0.0; + int fastestIndex = 0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->endAngles[i] = newJoints[i]; + angle_diff[i] = newTrajectory->endAngles[i] - nowAngles[i]; + float abs_diff = fabs(angle_diff[i]); + if (abs_diff > max_angle) { + max_angle = abs_diff; + fastestIndex = i; + } + } + max_velocity = fabs(newTrajectory->aim_velocity[fastestIndex]); + if (max_velocity * (ARM_FOLLOWING_CHECKING_STEP * 2 + (max_accelerate_time_ - 1) * 0.5) >= max_angle) { + max_velocity = max_angle / (ARM_FOLLOWING_CHECKING_STEP * 2 + (max_accelerate_time_ - 1) * 0.5); + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + if (max_angle < 0.0001) { + newTrajectory->aim_velocity[i] = 0; + } else { + newTrajectory->aim_velocity[i] = max_velocity * angle_diff[i] / max_angle; + } + } + newTrajectory->uniform_time_step += max_angle / max_velocity; + return 0; +} + +int TrapezoidalTrajectoryKinematics::ForwardKinematics(float *jointAngles, float *endEffectorPose) +{ + if (!rmService_) + { + return UNKNOWN_ERR; // Error: RM_Service not initialized + } + + // Call the RM_Service's ForwardKinematics method + rm_pose_t pose = rmService_->rm_algo_forward_kinematics(NULL, jointAngles); + endEffectorPose[POSE_POSITION_X] = pose.position.x; + endEffectorPose[POSE_POSITION_Y] = pose.position.y; + endEffectorPose[POSE_POSITION_Z] = pose.position.z; + endEffectorPose[POSE_QUATERNION_X] = pose.quaternion.x; + endEffectorPose[POSE_QUATERNION_Y] = pose.quaternion.y; + endEffectorPose[POSE_QUATERNION_Z] = pose.quaternion.z; + endEffectorPose[POSE_QUATERNION_W] = pose.quaternion.w; + return 0; +} + +int TrapezoidalTrajectoryKinematics::InverseKinematics(const float *endEffectorPose, float *jointAngles) +{ + if (!rmService_) + { + return UNKNOWN_ERR; // Error: RM_Service not initialized + } + + float nowJoints_[ARM_DOF] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; + for (int i = 0; i < USED_ARM_DOF; i++) { + nowJoints_[i] = jointAngles[i]; + } + rm_inverse_kinematics_params_t inverse_params; + memcpy(inverse_params.q_in, nowJoints_, sizeof(nowJoints_)); + inverse_params.q_pose.position.x = endEffectorPose[POSE_POSITION_X]; + inverse_params.q_pose.position.y = endEffectorPose[POSE_POSITION_Y]; + inverse_params.q_pose.position.z = endEffectorPose[POSE_POSITION_Z]; + inverse_params.q_pose.quaternion.x = endEffectorPose[POSE_QUATERNION_X]; + inverse_params.q_pose.quaternion.y = endEffectorPose[POSE_QUATERNION_Y]; + inverse_params.q_pose.quaternion.z = endEffectorPose[POSE_QUATERNION_Z]; + inverse_params.q_pose.quaternion.w = endEffectorPose[POSE_QUATERNION_W]; + inverse_params.flag = 0; + + int result = rmService_->rm_algo_inverse_kinematics(NULL, inverse_params, nowJoints_); + if (result != 0){ + return ARM_AIM_CANNOT_REACH; // Inverse kinematics failed + } + memcpy(jointAngles, nowJoints_, sizeof(float) * USED_ARM_DOF); + return 0; +} \ No newline at end of file diff --git a/rm_arm_control/src/goal_manager.cpp b/rm_arm_control/src/goal_manager.cpp new file mode 100644 index 0000000..606a9fb --- /dev/null +++ b/rm_arm_control/src/goal_manager.cpp @@ -0,0 +1,128 @@ +#include +#include "goal_manager.hpp" + +GoalManager::GoalManager() + : startGoalIndex_(0), endGoalIndex_(0), goalFullFlag_(0), currentGoalRunOffFlag_(0) +{ + memset(nowJointsGoalList_, 0, sizeof(nowJointsGoalList_)); + memset(goalIndexList_, 0, sizeof(goalIndexList_)); +} + +GoalManager::~GoalManager() {} + +int GoalManager::AddGoal(const float points[GOAL_DATA_LENGTH], const int64_t &index, int type) +{ + if (goalFullFlag_ == 1) { + return -1; + } + memcpy(nowJointsGoalList_[endGoalIndex_], points, sizeof(float) * GOAL_DATA_LENGTH); + goalIndex[index] = endGoalIndex_; + goalIndexList_[endGoalIndex_] = index; + goalResultList_[endGoalIndex_] = 0; + goalTypeList_[endGoalIndex_] = type; + endGoalIndex_++; + if (endGoalIndex_ >= MAX_ARM_GOAL_COUNT) { + endGoalIndex_ = 0; + } + if (endGoalIndex_ == startGoalIndex_) { + goalFullFlag_ = 1; + } + return 0; +} + +int GoalManager::ConsumeGoal() +{ + if (startGoalIndex_ == endGoalIndex_ && goalFullFlag_ == 0) { + return -1; + } + goalIndex.erase(goalIndexList_[startGoalIndex_]); + startGoalIndex_++; + if (startGoalIndex_ >= MAX_ARM_GOAL_COUNT) { + startGoalIndex_ = 0; + } + currentGoalRunOffFlag_ = 0; + goalFullFlag_ = 0; + return 0; +} + +const float* GoalManager::GetGoal() const +{ + if (startGoalIndex_ == endGoalIndex_ && goalFullFlag_ == 0) { + return nullptr; + } + return nowJointsGoalList_[startGoalIndex_]; +} + +int GoalManager::RemoveGoal(int64_t index) +{ + auto it = goalIndex.find(index); + if (it == goalIndex.end()) { + return -1; + } + int delIndex = it->second; + goalResultList_[delIndex] = ARM_GOAL_CANCELLED; + return 0; +} + +void GoalManager::ClearGoals() +{ + startGoalIndex_ = 0; + endGoalIndex_ = 0; + goalFullFlag_ = 0; + goalIndex.clear(); +} + +int GoalManager::SetNowGoalResult(int result) +{ + if (startGoalIndex_ == endGoalIndex_ && goalFullFlag_ == 0) { + return -1; + } + goalResultList_[startGoalIndex_] = result; + if (goalTypeList_[startGoalIndex_] == GOAL_TYPE_POSE_STEPPING && result != 0) { + goalTypeList_[startGoalIndex_] = GOAL_TYPE_MOVING; + goalResultList_[startGoalIndex_] = 0; + } + return 0; +} + +int GoalManager::GetNowGoalResult() const +{ + if (startGoalIndex_ == endGoalIndex_ && goalFullFlag_ == 0) { + return -1; + } + return goalResultList_[startGoalIndex_]; +} + +int64_t GoalManager::GetGoalNowIndex() +{ + if (startGoalIndex_ == endGoalIndex_ && goalFullFlag_ == 0) { + return -1; + } + return goalIndexList_[startGoalIndex_]; +} + +int64_t GoalManager::GetCompeletedGoalNowIndex() +{ + if ((startGoalIndex_ == endGoalIndex_ && goalFullFlag_ == 0) || currentGoalRunOffFlag_ == 0) { + return -1; + } + return goalIndexList_[startGoalIndex_]; +} + +int GoalManager::GetGoalType() const +{ + if (startGoalIndex_ == endGoalIndex_ && goalFullFlag_ == 0) { + return -1; + } + return goalTypeList_[startGoalIndex_]; +} + +void GoalManager::GoalRunOff() +{ + currentGoalRunOffFlag_ = 1; +} + +int GoalManager::GetRunOffFlag() const +{ + return currentGoalRunOffFlag_; +} diff --git a/rm_arm_control/src/init_set.cpp b/rm_arm_control/src/init_set.cpp new file mode 100644 index 0000000..2dd3f65 --- /dev/null +++ b/rm_arm_control/src/init_set.cpp @@ -0,0 +1,82 @@ +#include "arm_driver_define.hpp" +#include "rm_arm_node.hpp" +#include + +std::thread publicThread_; + +void PublicThread(ArmDriverDefault *armDriver) +{ + while (rclcpp::ok()) { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + armDriver->PublicThreadUpdate(); + } +} + +void custom_api_log(const char* message, va_list args) +{ + if (!message) { + fprintf(stderr, "Error: message is a null pointer"); + return; + } + + char buffer[1024]; + vsnprintf(buffer, sizeof(buffer), message, args); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), " %s", buffer); +} + +int InitRmDriver2(RmArmDriverAndKinematics **armDriver, RmArmDriverAndKinematics **armKinematics) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Initializing rm arm driver...\n"); + *armDriver = new RmArmDriverAndKinematics(); + (*armDriver)->SetCustomApiLog(custom_api_log); + (*armDriver)->RegArmStatusCallback(RmArmNode::CallbackRealtimeArmJointState); + int initResult = (*armDriver)->Init(); + if (initResult != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to initialize rm arm driver. %d", initResult); + return UNKNOWN_ERR; + } + + *armKinematics = *armDriver; + return 0; +} + +int InitSimulatorDriver(ArmDriverDefault **armDriver, TrapezoidalTrajectoryKinematics **armKinematics) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Initializing rm arm driver...\n"); + *armDriver = new ArmDriverDefault(); + (*armDriver)->RegArmStatusCallback(RmArmNode::CallbackRealtimeArmJointState); + int initResult = (*armDriver)->Init(); + if (initResult != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to initialize arm driver. %d", initResult); + return UNKNOWN_ERR; + } + *armKinematics = new TrapezoidalTrajectoryKinematics(); + + std::thread(PublicThread, *armDriver).detach(); + return 0; +} + +int InitRmArmDriver(ArmDriverDefault **armDriver, TrapezoidalTrajectoryKinematics **armKinematics) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Initializing rm arm driver...\n"); + auto rmArmDriver = new RmArmDriver(); + rmArmDriver->SetCustomApiLog(custom_api_log); + rmArmDriver->RegArmStatusCallback(ArmDriverDefault::CallArmStatusCallback); + int initResult = rmArmDriver->Init(); + if (initResult != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to initialize rm arm driver. %d", initResult); + return UNKNOWN_ERR; + } + + *armDriver = new ArmDriverDefault(); + (*armDriver)->RegArmStatusCallback(RmArmNode::CallbackRealtimeArmJointState); + (*armDriver)->RegArmMoveCallback(RmArmDriver::ArmMove); + initResult = (*armDriver)->Init(); + if (initResult != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to initialize arm driver. %d", initResult); + return UNKNOWN_ERR; + } + + *armKinematics = new TrapezoidalTrajectoryKinematics(rmArmDriver->rmService_); + return 0; +} \ No newline at end of file diff --git a/rm_arm_control/src/main.cpp b/rm_arm_control/src/main.cpp new file mode 100644 index 0000000..347b40d --- /dev/null +++ b/rm_arm_control/src/main.cpp @@ -0,0 +1,23 @@ +#include "arm_driver_define.hpp" +#include "rm_arm_node.hpp" + +int main(int argc, char *argv[]) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Starting rm_arm_control node..."); + + rclcpp::init(argc, argv); + + ArmDriver *armDriver = NULL; + Kinematics *armKinematics = NULL; + int initResult = ArmInitFunc(&armDriver, &armKinematics); + if (initResult != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to initialize rm arm driver. %d", initResult); + return UNKNOWN_ERR; + } + + auto rm_arm_control = std::make_shared(armDriver, armKinematics); + + rclcpp::spin(rm_arm_control); + + rclcpp::shutdown(); + return 0; +} \ No newline at end of file diff --git a/rm_arm_control/src/rm_arm_handler.cpp b/rm_arm_control/src/rm_arm_handler.cpp new file mode 100644 index 0000000..a1443b4 --- /dev/null +++ b/rm_arm_control/src/rm_arm_handler.cpp @@ -0,0 +1,285 @@ +#include "rm_arm_handler.hpp" + +const float maxJointSpeedList[USED_ARM_DOF] = {4.0, 4.0, 4.0, 4.0, 4.0, 4.0}; + +RmArmHandler::RmArmHandler(ArmDriver *driver, int armType, sem_t *sem, KinematicsManager *trapezoidalTrajectory): + armType_(armType), driver_(driver), trapezoidalTrajectory_(trapezoidalTrajectory) +{ + goalManager_ = new GoalManager(); + armStatus = ARM_STATUS_ERROR; + sem_ = sem; + memset(nowJoints_, 0, sizeof(nowJoints_)); + memset(nextJoints_, 0, sizeof(nextJoints_)); + + armStatus = ARM_STATUS_READY; +} + +RmArmHandler::~RmArmHandler() +{ + if (goalManager_ != NULL) { + delete goalManager_; + goalManager_ = NULL; + } + if (trapezoidalTrajectory_ != NULL) { + delete trapezoidalTrajectory_; + trapezoidalTrajectory_ = NULL; + } +} + +void PrintData(ArmStatusCallbackData *data) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "==================MYCALLBACK=================="); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "errCode: %d", data->errCode); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "current:"); + for (size_t i = 0; i < USED_ARM_DOF; i++){ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%.6f ", data->jointCurrent[i]); + } + + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "enable:"); + for (size_t i = 0; i < USED_ARM_DOF; i++){ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%d ", data->jointEnFlag[i]); + } + + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "error code:"); + for (size_t i = 0; i < USED_ARM_DOF; i++){ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%d ", data->jointErrCode[i]); + } + + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "position:"); + for (size_t i = 0; i < USED_ARM_DOF; i++){ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%.6f ", data->jointAngle[i]); + } + + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "speed:"); + for (size_t i = 0; i < USED_ARM_DOF; i++){ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%.6f ", data->jointSpeed[i]); + } + + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "temperature:"); + for (size_t i = 0; i < USED_ARM_DOF; i++){ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%.6f ", data->jointTemp[i]); + } + + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "voltage:"); + for (size_t i = 0; i < USED_ARM_DOF; i++){ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%.6f ", data->jointVoltage[i]); + } + +} + +void RmArmHandler::ArmDealCallBackInfo(ArmStatusCallbackData *data) +{ + ARM_STATUS_E temp = ARM_STATUS_READY; + for (size_t i = 0; i < USED_ARM_DOF; i++) + { + if (fabs(nowJoints_[i] - data->jointAngle[i]) > 0.02) { + temp = ARM_STATUS_WAITING; + } + nowJoints_[i] = data->jointAngle[i]; + } + if (armStatus == ARM_STATUS_WAITING && temp == ARM_STATUS_READY) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ARM_STATUS_READY."); + armStatus = ARM_STATUS_READY; + for (size_t i = 0; i < USED_ARM_DOF; i++) { + nextJoints_[i] = nowJoints_[i]; + } + sem_post(sem_); + } else if (armStatus == ARM_STATUS_READY && temp == ARM_STATUS_WAITING) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ARM_STATUS_WAITING."); + armStatus = ARM_STATUS_WAITING; + } + /*if (temp != ARM_STATUS_READY){ + PrintData(data); + }*/ +} + +int RmArmHandler::AddNextPoint(float points[GOAL_DATA_LENGTH], const int64_t &index, int type) +{ + std::unique_lock lock(rw_mutex_); + return goalManager_->AddGoal(points, index, type); +} + +int RmArmHandler::AddNextPointFromPoseMoving(const float pose[POSE_DIMENSION], const int64_t &index) +{ + float q_out[GOAL_DATA_LENGTH] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; + for (int i = 0; i < USED_ARM_DOF; i++) { + q_out[i] = nextJoints_[i]; + } + int result = trapezoidalTrajectory_->armKinematics_->InverseKinematics(pose, q_out); + if (result == 0) { + std::unique_lock lock(rw_mutex_); + return goalManager_->AddGoal(q_out, index, GOAL_TYPE_MOVING); + } + return result; +} + +int RmArmHandler::GetNextPointFromPoseStepping(const float pose[POSE_DIMENSION], float *joints) +{ + float poseTemp[POSE_DIMENSION] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; + int result = trapezoidalTrajectory_->armKinematics_->ForwardKinematics(nextJoints_, poseTemp); + if (result != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "ForwardKinematics error."); + return UNKNOWN_ERR; + } + for (int i = 0; i < POSE_DIMENSION; i++) { + poseTemp[i] = pose[i] + poseTemp[i]; + if (fabs(poseTemp[i]) < 0.0001) { + poseTemp[i] = 0.0f; + } + } + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Current pose:%.6f %.6f %.6f %.6f %.6f %.6f %.6f", + poseTemp[0], poseTemp[1], poseTemp[2], poseTemp[3], poseTemp[4], poseTemp[5], poseTemp[6]); + float q_out[GOAL_DATA_LENGTH] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; + for (int i = 0; i < USED_ARM_DOF; i++) { + q_out[i] = nextJoints_[i]; + } + result = trapezoidalTrajectory_->armKinematics_->InverseKinematics(poseTemp, q_out); + if (result != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "InverseKinematics error."); + return ARM_AIM_CANNOT_REACH; + } + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Next joints:%.6f %.6f %.6f %.6f %.6f %.6f", + q_out[0], q_out[1], q_out[2], q_out[3], q_out[4], q_out[5]); + for (int i = 0; i < USED_ARM_DOF; i++) { + joints[i] = q_out[i]; + } + return 0; +} + +int RmArmHandler::AddNextPointFromPose(const float pose[POSE_DIMENSION], const int64_t &index, int type) +{ + if (type == GOAL_TYPE_MOVING) { + return AddNextPointFromPoseMoving(pose, index); + } else if (type == GOAL_TYPE_STEPPING) { + std::unique_lock lock(rw_mutex_); + return goalManager_->AddGoal(pose, index, GOAL_TYPE_POSE_STEPPING); + } + return -1; +} + +int RmArmHandler::DeletePoint(int64_t index) +{ + int nowIndex; + { + std::shared_lock lock(rw_mutex_); + nowIndex = goalManager_->GetGoalNowIndex(); + } + if (index == nowIndex) { + ArmStop(0); + /*Trajectory* nowTrajectory = trapezoidalTrajectory_->getNowTrajectory(); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "DeletePoint: stop trajectory. accs:%d, unis:%d, curs:%d", + nowTrajectory->accelerate_time_step, nowTrajectory->uniform_time_step, nowTrajectory->current_time_step);*/ + return 0; + } + std::unique_lock lock(rw_mutex_); + return goalManager_->RemoveGoal(index); +} + +void RmArmHandler::ArmRun(int64_t timeStamp) +{ + if (armStatus != ARM_STATUS_MOVING) { + return; + } + int result, type; + type = goalManager_->GetGoalType(); + result = trapezoidalTrajectory_->updateTrajectory(timeStamp, nextJoints_); + + if (driver_->ArmMove(nextJoints_, armType_) != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Error moving to joint space! "); + return; + } + + if (result == TRAJECTORY_COMPLETE) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Trajectory complete."); + if (type == GOAL_TYPE_POSE_STEPPING) { + const float* pose = goalManager_->GetGoal(); + result = trapezoidalTrajectory_->continuePoseSteppingTrajectory(nextJoints_, pose); + if (result != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "GetNextPointFromPoseStepping failed."); + ArmStop(ARM_AIM_CANNOT_REACH); + } + /*Trajectory* nowTrajectory = trapezoidalTrajectory_->getNowTrajectory(); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Pose stepping continue. accs:%d, unis:%d, curs:%d, vels:%f, %f, %f, %f, %f, %f", + nowTrajectory->accelerate_time_step, nowTrajectory->uniform_time_step, nowTrajectory->current_time_step, + nowTrajectory->aim_velocity[0], nowTrajectory->aim_velocity[1], nowTrajectory->aim_velocity[2], + nowTrajectory->aim_velocity[3], nowTrajectory->aim_velocity[4], nowTrajectory->aim_velocity[5]);*/ + } else { + int runOffFlag = goalManager_->GetRunOffFlag(); + if (runOffFlag == 0) { + std::unique_lock lock(rw_mutex_); + goalManager_->GoalRunOff(); + armStatus = ARM_STATUS_WAITING; + } + } + } +} + +int RmArmHandler::StartNewTrajectory() +{ + std::shared_lock lock(rw_mutex_); + const float* goal = goalManager_->GetGoal(); + if (goal == NULL) { + return ARM_NOW_NO_GOAL; + } + if (goalManager_->GetNowGoalResult() != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to start new trajectory because canceled. GoalRunOff1."); + goalManager_->GoalRunOff(); + return ARM_GOAL_CANCELLED; + } + float start[USED_ARM_DOF]; + for (int i = 0; i < USED_ARM_DOF; i++) { + start[i] = nextJoints_[i]; + } + int goalType = goalManager_->GetGoalType(); + int result = trapezoidalTrajectory_->computeTrajectory(start, goal, goalType); + if (result != 0) { + goalManager_->GoalRunOff(); + } + /*Trajectory* nowTrajectory = trapezoidalTrajectory_->getNowTrajectory(); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Pose stepping continue. accs:%d, unis:%d, vels:%f, %f, %f, %f, %f, %f", + nowTrajectory->accelerate_time_step, nowTrajectory->uniform_time_step, + nowTrajectory->aim_velocity[0], nowTrajectory->aim_velocity[1], nowTrajectory->aim_velocity[2], + nowTrajectory->aim_velocity[3], nowTrajectory->aim_velocity[4], nowTrajectory->aim_velocity[5]);*/ + return result; +} + +void RmArmHandler::ArmMove() +{ + armStatus = ARM_STATUS_MOVING; +} + +void RmArmHandler::ArmStop(int result) +{ + std::unique_lock lock(rw_mutex_); + trapezoidalTrajectory_->stopTrajectory(); + goalManager_->SetNowGoalResult(result); +} + +void RmArmHandler::ArmStopStart(int result) +{ + std::unique_lock lock(rw_mutex_); + trapezoidalTrajectory_->stopTrajectory(); + goalManager_->SetNowGoalResult(result); + goalManager_->GoalRunOff(); +} + +int RmArmHandler::GoalReached() +{ + std::unique_lock lock(rw_mutex_); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "GoalReached, locked."); + int result = goalManager_->GetNowGoalResult(); + goalManager_->ConsumeGoal(); + return result; +} + +int64_t RmArmHandler::GetCurrentRunOffGoalIndex() +{ + std::shared_lock lock(rw_mutex_); + return goalManager_->GetCompeletedGoalNowIndex(); +} + +int64_t RmArmHandler::GetCurrentGoalIndex() +{ + std::shared_lock lock(rw_mutex_); + return goalManager_->GetGoalNowIndex(); +} \ No newline at end of file diff --git a/rm_arm_control/src/rm_arm_node.cpp b/rm_arm_control/src/rm_arm_node.cpp new file mode 100644 index 0000000..9827547 --- /dev/null +++ b/rm_arm_control/src/rm_arm_node.cpp @@ -0,0 +1,488 @@ +#include "arm_define.h" +#include "rm_arm_simulator.hpp" +#include "rm_arm_node.hpp" + +static ArmSimulator *armSimulator_; + +using ArmGoalSharedPtr = + std::shared_ptr; + +namespace ArmCommandHash +{ + using ArmCommand = int(*)(RmArmHandler *handle, const ArmGoalSharedPtr goal); + + static int AngleStepOn(RmArmHandler *handle, const ArmGoalSharedPtr goal) + { + if (goal->data_length.data_length != USED_ARM_DOF) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "AngleStepOn data length error."); + return -1; + } + float points[GOAL_DATA_LENGTH] = {0}; + std::string speeds = "aim speed "; + for (int i = 0; i < USED_ARM_DOF; i++) { + points[i] = goal->data_array[i]; + speeds += std::to_string(points[i]) + " "; + } + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%s", speeds.c_str()); + int result = handle->AddNextPoint(points, goal->command_id, GOAL_TYPE_STEPPING); + return result; + } + + static int AngleDirectMove(RmArmHandler *handle, std::shared_ptr goal) + { + if (goal->data_length.data_length != USED_ARM_DOF) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "AngleDirectMove data length error."); + return -1; + } + float points[GOAL_DATA_LENGTH] = {0}; + for (int i = 0; i < USED_ARM_DOF; i++) { + points[i] = goal->data_array[i]; + } + if (armSimulator_->CheckJointsAngleLimit(points) != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "AngleDirectMove joints limit error."); + return ARM_AIM_CANNOT_REACH; + } + int result = handle->AddNextPoint(points, goal->command_id, GOAL_TYPE_MOVING); + return result; + } + + static int PoseStepOn(RmArmHandler *handle, std::shared_ptr goal) + { + if (goal->data_length.data_length != POSE_DIMENSION) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "PoseStepOn data length error."); + return -1; + } + float points[GOAL_DATA_LENGTH] = {0}; + for (int i = 0; i < POSE_DIMENSION; i++) { + points[i] = goal->data_array[i]; + } + return handle->AddNextPointFromPose(points, goal->command_id, GOAL_TYPE_STEPPING); + } + + static int PoseDirectMove(RmArmHandler *handle, std::shared_ptr goal) + { + if (goal->data_length.data_length != POSE_DIMENSION) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "PoseDirectMove data length error."); + return -1; + } + float points[GOAL_DATA_LENGTH] = {0}; + for (int i = 0; i < POSE_DIMENSION; i++) { + points[i] = goal->data_array[i]; + } + return handle->AddNextPointFromPose(points, goal->command_id, GOAL_TYPE_MOVING); + } + + const std::unordered_map armCommandMap = { + {ARM_COMMAND_TYPE_ANGLE_STEP_ON, AngleStepOn}, + {ARM_COMMAND_TYPE_ANGLE_DIRECT_MOVE, AngleDirectMove}, + {ARM_COMMAND_TYPE_POSE_STEP_ON, PoseStepOn}, + {ARM_COMMAND_TYPE_POSE_DIRECT_MOVE, PoseDirectMove} + }; +} + +static RmArmNode *localNodePtr = NULL; +RmArmHandler *RmArmNode::leftArmHandler_; +RmArmHandler *RmArmNode::rightArmHandler_; +rclcpp::Publisher::SharedPtr RmArmNode::armStatesPub_; +sensor_msgs::msg::JointState RmArmNode::armStates; + +static RmArmHandler *GetArmHandler(RmArmNode *node, int body_id) +{ + RmArmHandler *handle = NULL; + if (body_id == LEFT_ARM) { + handle = node->leftArmHandler_; + } else if (body_id == RIGHT_ARM) { + handle = node->rightArmHandler_; + } + return handle; +} + +#define LEFT_ARM_JOINT_START_INDEX 9 +#define RIGHT_ARM_JOINT_START_INDEX 15 +#define JOINT_ALL_CNT 29 +// 机器人控制器构造函数 +RmArmNode::RmArmNode(ArmDriver *armDriver, Kinematics *kinematics) : Node("rm_arm_control"), armDriver_(armDriver) +{ + localNodePtr = this; + sem_init(&sem_, 0, 0); + + KinematicsManager *leftTrajectory = new KinematicsManager(kinematics, LEFT_ARM); + KinematicsManager *rightTrajectory = new KinematicsManager(kinematics, RIGHT_ARM); + + leftArmHandler_ = new RmArmHandler(armDriver_, LEFT_ARM, &sem_, leftTrajectory); + if (leftArmHandler_ != NULL && leftArmHandler_->armStatus == ARM_STATUS_READY) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Left arm handler initialization success."); + } else { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Left arm handler initialization failed."); + } + + rightArmHandler_ = new RmArmHandler(armDriver_, RIGHT_ARM, &sem_, rightTrajectory); + if (rightArmHandler_ != NULL && rightArmHandler_->armStatus == ARM_STATUS_READY) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Right arm handler initialization success."); + } else { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Right arm handler initialization failed."); + } + + armStatesPub_ = this->create_publisher("joint_states", 10); + + this->action_server_ = rclcpp_action::create_server( + this, + "ArmAction", + std::bind(&RmArmNode::ArmActionGoal, this, std::placeholders::_1, std::placeholders::_2), + std::bind(&RmArmNode::ArmActionCancel, this, std::placeholders::_1), + std::bind(&RmArmNode::ArmActionAccepted, this, std::placeholders::_1)); + + this->declare_parameter("robot_description", ""); + std::string urdf_string = this->get_parameter("robot_description").as_string(); + /*leftArmHandler_->nowJoints_[0] = 180.0; + leftArmHandler_->nowJoints_[1] = 180.0;*/ + if (urdf_string != "") { + armStates.name = { + "left_behind_hip_joint","left_behind_leg_joint","left_behind_wheel_joint","right_behind_hip_joint", + "right_behind_leg_joint","right_behind_wheel_joint","body_joint","body_2_joint","head_joint", + "left_joint1","left_joint2","left_joint3","left_joint4","left_joint5", "left_joint6", + "right_joint1","right_joint2","right_joint3","right_joint4","right_joint5", "right_joint6", + "left_front_roll_joint","left_front_hip_joint","left_front_knee_joint", + "left_front_wheel_joint","right_front_roll_joint","right_front_hip_joint","right_front_knee_joint","right_front_wheel_joint"}; + armStates.position.resize(JOINT_ALL_CNT, 0.0); + armStates.header.frame_id = "base_link"; + armSimulator_ = new ArmSimulator(urdf_string, leftArmHandler_->nowJoints_, rightArmHandler_->nowJoints_, + leftArmHandler_->trapezoidalTrajectory_, rightArmHandler_->trapezoidalTrajectory_); + robotDescriptionSub_ = NULL; + } else { + armSimulator_ = NULL; + robotDescriptionSub_ = this->create_subscription + ("robot_description", 10, std::bind(&RmArmNode::CallbackGetRobotDescription, this, std::placeholders::_1)); + } + + std::thread{std::bind(&RmArmNode::ArmActionCheck, this)}.detach(); + std::thread{std::bind(&RmArmNode::ArmActionExecute, this)}.detach(); + + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Robot arm control node initialized."); +} + +RmArmNode::~RmArmNode() +{ + armStatesPub_.reset(); + delete leftArmHandler_; + delete rightArmHandler_; + delete armSimulator_; +} + +void RmArmNode::CallbackGetRobotDescription(const std_msgs::msg::String::SharedPtr msg) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Received robot_description message."); + if (armSimulator_ == NULL) { + armStates.name = { + "left_behind_hip_joint","left_behind_leg_joint","left_behind_wheel_joint","right_behind_hip_joint", + "right_behind_leg_joint","right_behind_wheel_joint","body_joint","body_2_joint","head_joint", + "left_shoulder_joint","left_arm_1_joint","left_arm_2_joint","left_arm_3_joint","left_arm_4_joint", + "left_wrist_joint","right_joint1","right_joint2","right_joint3","right_joint4", + "right_joint5","right_joint6","left_front_roll_joint","left_front_hip_joint","left_front_knee_joint", + "left_front_wheel_joint","right_front_roll_joint","right_front_hip_joint","right_front_knee_joint","right_front_wheel_joint"}; + armStates.position.resize(JOINT_ALL_CNT, 0.0); + armStates.header.frame_id = "base_link"; + armSimulator_ = new ArmSimulator(msg, leftArmHandler_->nowJoints_, rightArmHandler_->nowJoints_, + leftArmHandler_->trapezoidalTrajectory_, rightArmHandler_->trapezoidalTrajectory_); + } +} + +rclcpp_action::GoalResponse RmArmNode::ArmActionGoal( + const rclcpp_action::GoalUUID & uuid, + std::shared_ptr goal) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Received goal request."); + // Accept the goal + if (ArmCommandHash::armCommandMap.find(goal->data_type.action_type) == ArmCommandHash::armCommandMap.end()) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Received goal with invalid command id: %d", goal->data_type.action_type); + return rclcpp_action::GoalResponse::REJECT; + } + RmArmHandler *handle = GetArmHandler(this, goal->body_id.body_id); + if (handle == NULL) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "arm validation error."); + return rclcpp_action::GoalResponse::REJECT; + } + if (handle->armStatus == ARM_STATUS_ERROR || handle->armStatus == ARM_STATUS_INIT) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Arm in error status."); + return rclcpp_action::GoalResponse::REJECT; + } + int result = ArmCommandHash::armCommandMap.at(goal->data_type.action_type)(handle, goal); + if (result != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to process the goal."); + return rclcpp_action::GoalResponse::REJECT; + } + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; +} + +rclcpp_action::CancelResponse RmArmNode::ArmActionCancel( + const std::shared_ptr goal_handle) +{ + ArmGoalSharedPtr goal = goal_handle->get_goal(); + int64_t index = goal->command_id; + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Received request to cancel goal. Index: %ld", index); + int result = 0; + RmArmHandler *handle = GetArmHandler(this, goal->body_id.body_id); + if (handle == NULL) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "arm validation error."); + return rclcpp_action::CancelResponse::REJECT; + } + result = handle->DeletePoint(goal->command_id); + if (result != 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to cancel the goal."); + return rclcpp_action::CancelResponse::REJECT; + } + // Accept the cancel request + return rclcpp_action::CancelResponse::ACCEPT; +} + +void RmArmNode::ArmActionFeedback(int coll) +{ + float leftPose[POSE_DIMENSION] = {0}; + float rightPose[POSE_DIMENSION] = {0}; + RmArmHandler *leftHandle = GetArmHandler(this, LEFT_ARM); + RmArmHandler *rightHandle = GetArmHandler(this, RIGHT_ARM); + if (leftHandle != NULL && leftHandle->armStatus != ARM_STATUS_ERROR && leftHandle->armStatus != ARM_STATUS_INIT) { + leftHandle->trapezoidalTrajectory_->armKinematics_->ForwardKinematics(leftHandle->nowJoints_, leftPose); + } + if (rightHandle != NULL && rightHandle->armStatus != ARM_STATUS_ERROR && rightHandle->armStatus != ARM_STATUS_INIT) { + rightHandle->trapezoidalTrajectory_->armKinematics_->ForwardKinematics(rightHandle->nowJoints_, rightPose); + } + for (auto it = goal_handles_.begin(); it != goal_handles_.end(); ++it) { + auto goal_handle = it->second; + ArmGoalSharedPtr goal = goal_handle->get_goal(); + RmArmHandler *handle = GetArmHandler(this, goal->body_id.body_id); + if (handle == NULL) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "arm validation error."); + continue; + } + if (handle->armStatus == ARM_STATUS_ERROR || handle->armStatus == ARM_STATUS_INIT) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Arm in error status."); + continue; + } + float *pose = (goal->body_id.body_id == LEFT_ARM) ? leftPose : rightPose; + + auto feedback = std::make_shared(); + feedback->command_id = goal->command_id; + feedback->int_lenth = 1; + feedback->float_length.data_length = POSE_DIMENSION; + feedback->int_data_array = {coll}; + feedback->float_data_array = {pose[0], pose[1], pose[2], pose[3], pose[4], pose[5], pose[6]}; + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Publishing feedback for command id: %ld, joints: %f, %f, %f, %f, %f, %f, %f", + feedback->command_id, feedback->float_data_array[0], feedback->float_data_array[1], + feedback->float_data_array[2], feedback->float_data_array[3], + feedback->float_data_array[4], feedback->float_data_array[5], feedback->float_data_array[6]); + goal_handle->publish_feedback(feedback); + } +} + +void RmArmNode::ArmActionFinish(int64_t index, int result) +{ + rclcpp::Time endColTime = this->get_clock()->now(); + auto goal_handle_pair = goal_handles_.find(index); + if (goal_handle_pair != goal_handles_.end()) { + auto goal_handle = goal_handle_pair->second; + auto goalResult = std::make_shared(); + float pose[POSE_DIMENSION] = {0}; + RmArmHandler *handle = GetArmHandler(this, goal_handle->get_goal()->body_id.body_id); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Finishing goal joints: %f, %f, %f, %f, %f, %f", + handle->nowJoints_[0], handle->nowJoints_[1], handle->nowJoints_[2], + handle->nowJoints_[3], handle->nowJoints_[4], handle->nowJoints_[5]); + if (handle != NULL && handle->armStatus != ARM_STATUS_ERROR && handle->armStatus != ARM_STATUS_INIT) { + handle->trapezoidalTrajectory_->armKinematics_->ForwardKinematics(handle->nowJoints_, pose); + } + goalResult->end_time = endColTime.nanoseconds(); + goalResult->result.result = result; + goalResult->command_id = index; + goalResult->pose.position.x = pose[POSE_POSITION_X]; + goalResult->pose.position.y = pose[POSE_POSITION_Y]; + goalResult->pose.position.z = pose[POSE_POSITION_Z]; + goalResult->pose.orientation.x = pose[POSE_QUATERNION_X]; + goalResult->pose.orientation.y = pose[POSE_QUATERNION_Y]; + goalResult->pose.orientation.z = pose[POSE_QUATERNION_Z]; + goalResult->pose.orientation.w = pose[POSE_QUATERNION_W]; + if (goal_handle->is_canceling()) { + goal_handle->canceled(goalResult); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Goal %ld canceled.", index); + } else if (result == OK){ + goal_handle->succeed(goalResult); + } else { + goal_handle->abort(goalResult); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Goal %ld aborted.", index); + } + goal_handles_.erase(index); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Goal %ld finished. now aim cnt %ld.", index, goal_handles_.size()); + } else { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Goal handle not found for index %ld.", index); + } +} + +void RmArmNode::StartNewGoal(RmArmHandler *handle) +{ + if (goal_handles_.size() == 0) { + return; + } + int ret; + int64_t index = handle->GetCurrentRunOffGoalIndex(); + if (index != -1) { + ret = handle->GoalReached(); + ArmActionFinish(index, ret); + } + index = handle->GetCurrentGoalIndex(); + if (goal_handles_.find(index) == goal_handles_.end()) { + return; + } + do { + ret = handle->StartNewTrajectory(); + if (ret == 0) { + // ret = armSimulator_->UpdateCollisionForNewGoal(handle->armType_); + if (ret == SAFE) { + handle->ArmMove(); + } else { + handle->ArmStopStart(ARM_COLLISION); + ret = ARM_COLLISION; + } + } + if (ret != ARM_NOW_NO_GOAL && ret != 0) { + index = handle->GetCurrentRunOffGoalIndex(); + handle->GoalReached(); + ArmActionFinish(index, ret); + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to start new goal with error code: %d.", ret); + } + } while (ret != 0 && ret != ARM_NOW_NO_GOAL); +} + +int g_checkCnt = 0; +int64_t g_totalColTime = 0; +int64_t g_maxColTime = 0; + +void RmArmNode::ArmActionCheck() +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Checking\n"); + rclcpp::Time startTime = get_clock()->now(); + int64_t nextCheckPoint = startTime.nanoseconds() + ARM_FOLLOWING_CHECKING; + struct timespec timeout; + timeout.tv_sec = 0; + timeout.tv_nsec = ARM_FOLLOWING_CHECKING; // 20 milliseconds + int step = 0; + bool busy = false; + + int64_t maxUsedTime = 0; + + // Execute the goal + while (rclcpp::ok()) { + if (!busy) { + int result = sem_timedwait(&sem_, &timeout); + if (leftArmHandler_ != NULL && (leftArmHandler_->armStatus == ARM_STATUS_READY)) { + StartNewGoal(leftArmHandler_); + } + if (rightArmHandler_ != NULL && (rightArmHandler_->armStatus == ARM_STATUS_READY)) { + StartNewGoal(rightArmHandler_); + } + } + int64_t currentTimeNs = get_clock()->now().nanoseconds(); + if (currentTimeNs >= nextCheckPoint) { + step++; + nextCheckPoint += ARM_FOLLOWING_CHECKING; + int coll = 0; //armSimulator_->CheckCollision(); + + g_checkCnt++; + int64_t durationCol = (get_clock()->now().nanoseconds() - currentTimeNs); + g_totalColTime += durationCol; + if (g_maxColTime < durationCol) { + g_maxColTime = durationCol; + } + if (g_checkCnt % 2000 == 0) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), + "Collision check avg time: %ld us, max time: %ld us", + g_totalColTime / g_checkCnt / 1000, g_maxColTime / 1000); + g_checkCnt = 0; + g_totalColTime = 0; + } + + if (coll != SAFE) { + // if (coll == ARM_AIM_CANNOT_REACH) { + leftArmHandler_->ArmStop(ARM_COLLISION); + rightArmHandler_->ArmStop(ARM_COLLISION); + ArmActionFeedback(coll); + step = 0; + } else if (step >= 5) { + ArmActionFeedback(coll); + step = 0; + } + } + + int64_t afterCheckTimeNs = get_clock()->now().nanoseconds(); + + if (afterCheckTimeNs >= nextCheckPoint) { + busy = true; + int64_t usedTime = afterCheckTimeNs - currentTimeNs; + if (usedTime > 10 * 1e6) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "arm action check loop is too slow!, %ld", + usedTime); + } + } else { + timeout.tv_nsec = nextCheckPoint - afterCheckTimeNs; + busy = false; + } + } +} + +void RmArmNode::ArmActionExecute() +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Executing\n"); + rclcpp::Time startTime = get_clock()->now(); + int64_t startTimeNs = startTime.nanoseconds(); + // Execute the goal + while (rclcpp::ok()) { + if (armSimulator_ != NULL) { + if (leftArmHandler_ != NULL) { + leftArmHandler_->ArmRun(startTimeNs); + } + if (rightArmHandler_ != NULL) { + rightArmHandler_->ArmRun(startTimeNs); + } + } + startTimeNs += ARM_FOLLOWING_PERIOD; + int64_t currentTimeNs = get_clock()->now().nanoseconds(); + int64_t sleepTime = (startTimeNs - (currentTimeNs)) / 1e3; + if (sleepTime > 0) { + std::this_thread::sleep_for(std::chrono::microseconds(sleepTime)); + } else { + if (sleepTime < -10 * 1e3) { + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "arm action execute loop is too slow!, %ld", + -sleepTime); + startTimeNs = currentTimeNs + ARM_FOLLOWING_PERIOD; + } + } + } +} + +void RmArmNode::ArmActionAccepted(const std::shared_ptr goal_handle) +{ + RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Goal accepted. Index: %ld", goal_handle->get_goal()->command_id); + // Start executing the goal + goal_handles_[goal_handle->get_goal()->command_id] = goal_handle; +} + +void RmArmNode::CallbackRealtimeArmJointState(ArmStatusCallbackData *data) +{ + if (data->armId == LEFT_ARM && leftArmHandler_ != NULL) { + leftArmHandler_->ArmDealCallBackInfo(data); + } + else if (data->armId == RIGHT_ARM && rightArmHandler_ != NULL) { + rightArmHandler_->ArmDealCallBackInfo(data); + } + if (armStatesPub_ != NULL && armSimulator_ != NULL) { + for (int i = LEFT_ARM_JOINT_START_INDEX; i < LEFT_ARM_JOINT_START_INDEX + USED_ARM_DOF; i++) { + armStates.position[i] = leftArmHandler_->nowJoints_[i - LEFT_ARM_JOINT_START_INDEX] * M_PI / 180.0f; + } + for (int i = RIGHT_ARM_JOINT_START_INDEX; i < RIGHT_ARM_JOINT_START_INDEX + USED_ARM_DOF; i++) { + armStates.position[i] = rightArmHandler_->nowJoints_[i - RIGHT_ARM_JOINT_START_INDEX] * M_PI / 180.0f; + } + armStates.header.stamp = localNodePtr->get_clock()->now(); + armStates.velocity = {}; + armStates.effort = {}; + // 发布消息 + armStatesPub_->publish(armStates); + } +} diff --git a/rm_arm_control/src/trapezoidal_trajectory.cpp b/rm_arm_control/src/trapezoidal_trajectory.cpp new file mode 100644 index 0000000..90d26ab --- /dev/null +++ b/rm_arm_control/src/trapezoidal_trajectory.cpp @@ -0,0 +1,368 @@ +#include +#include "trapezoidal_trajectory.hpp" + +TrapezoidalTrajectory::TrapezoidalTrajectory() + : max_velocity_(1.0), max_acceleration_(0.25) +{ + max_accelerate_time_ = 4; + max_accelerate_angle_ = max_velocity_ * max_accelerate_time_; + + nowTrajectoryIndex_ = -1; + trajectoryFullFlag_ = 0; + trajectoryHistory_[0].current_time_step = 0; + min_angle_for_pose_stepping_max_speed_ = ARM_FOLLOWING_CHECKING_STEP * max_velocity_ * 2; +} + +TrapezoidalTrajectory::~TrapezoidalTrajectory() {} + +Trajectory* TrapezoidalTrajectory::addTrajectory() +{ + nowTrajectoryIndex_++; + if (nowTrajectoryIndex_ >= MAX_TRAJECTORY_HISTORY) { + nowTrajectoryIndex_ = 0; + trajectoryFullFlag_ = 1; + } + return &trajectoryHistory_[nowTrajectoryIndex_]; +} + +void TrapezoidalTrajectory::computeMovingTrajectory(Trajectory *newTrajectory, const float *start, const float *end) +{ + float max_angle = 0.0; + float angle_diff[USED_ARM_DOF]; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->startAngles[i] = start[i]; + newTrajectory->endAngles[i] = end[i]; + angle_diff[i] = end[i] - start[i]; + float abs_diff = fabs(angle_diff[i]); + if (abs_diff > max_angle) { + max_angle = abs_diff; + } + } + if (max_angle < 0.01) { + newTrajectory->accelerate_time_step = 0; + newTrajectory->uniform_time_step = 0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->aim_velocity[i] = 0; + newTrajectory->now_acceleration[i] = 0; + newTrajectory->endAngles[i] = start[i]; + } + return; + } + float aim_velocity = max_velocity_; + if (max_angle < max_accelerate_angle_) { + newTrajectory->accelerate_time_step = static_cast(sqrt(max_angle / max_acceleration_)) + 1; + aim_velocity = max_angle / newTrajectory->accelerate_time_step; + newTrajectory->uniform_time_step = 0; + } else { + newTrajectory->accelerate_time_step = max_accelerate_time_; + newTrajectory->uniform_time_step = static_cast((max_angle - max_accelerate_angle_) / max_velocity_); + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->aim_velocity[i] = aim_velocity * angle_diff[i] / max_angle; + newTrajectory->now_acceleration[i] = newTrajectory->aim_velocity[i] / newTrajectory->accelerate_time_step; + } +} + +void TrapezoidalTrajectory::computeSteppingTrajectory(Trajectory *newTrajectory, const float *start, const float *speed) +{ + float maxSpeed = 0.0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->startAngles[i] = start[i]; + if (fabs(speed[i]) > max_velocity_) { + newTrajectory->aim_velocity[i] = (speed[i] > 0 ? 1 : -1) * max_velocity_; + } else { + newTrajectory->aim_velocity[i] = speed[i]; + } + if (fabs(newTrajectory->aim_velocity[i]) > maxSpeed) { + maxSpeed = fabs(newTrajectory->aim_velocity[i]); + } + } + newTrajectory->uniform_time_step = -1; + newTrajectory->accelerate_time_step = static_cast(maxSpeed / max_acceleration_) + 1; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->now_acceleration[i] = newTrajectory->aim_velocity[i] / newTrajectory->accelerate_time_step; + newTrajectory->endAngles[i] = 0; + } +} + +void TrapezoidalTrajectory::computePoseSteppingTrajectory(Trajectory *newTrajectory, const float *start, const float *end) +{ + float max_angle = 0.0; + float angle_diff[USED_ARM_DOF]; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->startAngles[i] = start[i]; + newTrajectory->endAngles[i] = end[i]; + angle_diff[i] = end[i] - start[i]; + float abs_diff = fabs(angle_diff[i]); + if (abs_diff > max_angle) { + max_angle = abs_diff; + } + } + if (max_angle < 0.01) { + newTrajectory->accelerate_time_step = 0; + newTrajectory->uniform_time_step = 0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->aim_velocity[i] = 0; + newTrajectory->now_acceleration[i] = 0; + newTrajectory->endAngles[i] = start[i]; + } + return; + } + float aim_velocity = max_velocity_; + newTrajectory->accelerate_time_step = max_accelerate_time_; + if (max_angle < min_angle_for_pose_stepping_max_speed_ - 0.5 * max_accelerate_angle_) { + aim_velocity = max_angle / (ARM_FOLLOWING_CHECKING_STEP * 2 - (max_accelerate_time_ - 1) * 0.5); + newTrajectory->uniform_time_step = ARM_FOLLOWING_CHECKING_STEP * 2 - max_accelerate_time_; + } else { + newTrajectory->uniform_time_step = static_cast((max_angle - (max_accelerate_angle_ - 1) * 0.5) / max_velocity_); + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->aim_velocity[i] = aim_velocity * angle_diff[i] / max_angle; + newTrajectory->now_acceleration[i] = newTrajectory->aim_velocity[i] / max_accelerate_time_; + } +} + +int TrapezoidalTrajectory::computeTrajectory(const float *start, const float *end, int type) +{ + Trajectory* newTrajectory = addTrajectory(); + newTrajectory->goalType = type; + newTrajectory->startTime = 0; + newTrajectory->stopTime = 0; + newTrajectory->current_time_step = 0; + if (type == GOAL_TYPE_MOVING) { + computeMovingTrajectory(newTrajectory, start, end); + } else if (type == GOAL_TYPE_POSE_STEPPING) { + computePoseSteppingTrajectory(newTrajectory, start, end); + } else { + computeSteppingTrajectory(newTrajectory, start, end); + } + return 0; +} + +int TrapezoidalTrajectory::checkStartTrajectory(int64_t startTime) +{ + if (nowTrajectoryIndex_ < 0) { + return -1; + } + if (trajectoryHistory_[nowTrajectoryIndex_].startTime != 0) { + return 0; + } + trajectoryHistory_[nowTrajectoryIndex_].startTime = startTime; + trajectoryHistory_[nowTrajectoryIndex_].stopTime = startTime + + (2 * trajectoryHistory_[nowTrajectoryIndex_].accelerate_time_step + + trajectoryHistory_[nowTrajectoryIndex_].uniform_time_step) * ARM_FOLLOWING_PERIOD; + return 0; +} + +int TrapezoidalTrajectory::updateTrajectory(float *aimAngles) +{ + // Update the aimAngles based on the computed trajectory + Trajectory* newTrajectory = &trajectoryHistory_[nowTrajectoryIndex_]; + newTrajectory->current_time_step++; + if (newTrajectory->current_time_step < newTrajectory->accelerate_time_step) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + float v = newTrajectory->now_acceleration[i] * newTrajectory->current_time_step; + aimAngles[i] += v; + } + } else if (newTrajectory->uniform_time_step == STEPPING_UNIFORM_TIME_STAMP || + newTrajectory->current_time_step < newTrajectory->accelerate_time_step + newTrajectory->uniform_time_step) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + aimAngles[i] += newTrajectory->aim_velocity[i]; + } + } else if (newTrajectory->current_time_step < 2 * newTrajectory->accelerate_time_step + newTrajectory->uniform_time_step) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + int decelerate_time_step = newTrajectory->current_time_step - newTrajectory->accelerate_time_step + - newTrajectory->uniform_time_step; + float v = newTrajectory->aim_velocity[i] - newTrajectory->now_acceleration[i] * decelerate_time_step; + if (v < 0) v = 0; + aimAngles[i] += v; + } + } else { + for (int i = 0; i < USED_ARM_DOF; ++i) { + aimAngles[i] = newTrajectory->endAngles[i]; + } + return TRAJECTORY_COMPELETE; + } + return TRAJECTORY_ONGOING; +} + +int TrapezoidalTrajectory::getAngleFromTime(float *aimAngles, int64_t timeStamp) +{ + if (nowTrajectoryIndex_ == -1) { + return OK; + } + int startIndex = nowTrajectoryIndex_ + 1; + int endIndex = trajectoryFullFlag_ == 1 ? startIndex : 0; + do { + startIndex = (startIndex + MAX_TRAJECTORY_HISTORY - 1) % MAX_TRAJECTORY_HISTORY; + Trajectory* traj = &trajectoryHistory_[startIndex]; + if (traj -> stopTime == 0) { + if (startIndex == nowTrajectoryIndex_) { + return ARM_NOW_FORCE_MOVING; + } + return UNKNOWN_ERR; + } + if (timeStamp >= traj->stopTime) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + aimAngles[i] = traj->endAngles[i]; + } + return 0; + } + if (timeStamp >= traj->startTime) { + int64_t time_diff = timeStamp - traj->startTime; + int time_step = static_cast(time_diff / ARM_FOLLOWING_PERIOD); + for (int i = 0; i < USED_ARM_DOF; ++i) { + float angle = traj->startAngles[i]; + if (time_step < traj->accelerate_time_step) { + angle += 0.5 * traj->now_acceleration[i] * time_step * time_step; + } else if (traj->uniform_time_step == STEPPING_UNIFORM_TIME_STAMP + || time_step < traj->accelerate_time_step + traj->uniform_time_step) { + angle += 0.5 * traj->now_acceleration[i] * traj->accelerate_time_step * (traj->accelerate_time_step); + angle += traj->aim_velocity[i] * (time_step - traj->accelerate_time_step); + } else if (time_step <= 2 * traj->accelerate_time_step + traj->uniform_time_step) { + int decelerate_time_step = time_step - traj->accelerate_time_step - traj->uniform_time_step; + angle += 0.5 * traj->now_acceleration[i] * (traj->accelerate_time_step) * (traj->accelerate_time_step); + angle += traj->aim_velocity[i] * (traj->uniform_time_step); + angle += traj->aim_velocity[i] * decelerate_time_step + - 0.5 * traj->now_acceleration[i] * decelerate_time_step * decelerate_time_step; + } else { + angle = traj->endAngles[i]; + } + aimAngles[i] = angle; + } + return 0; + } + } while (startIndex != endIndex); + return -1; +} + +static void getAngleForCheckingInner(Trajectory* traj, int timeStepOffset, float *aimAngles) +{ + int time_step = traj->current_time_step + timeStepOffset; + if (time_step >= traj->accelerate_time_step * 2 + traj->uniform_time_step + && traj->uniform_time_step != STEPPING_UNIFORM_TIME_STAMP) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + aimAngles[i] = traj->endAngles[i]; + } + return; + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + float angle = traj->startAngles[i]; + if (time_step < traj->accelerate_time_step) { + angle += 0.5 * traj->now_acceleration[i] * time_step * time_step; + } else if (time_step < traj->accelerate_time_step + traj->uniform_time_step || + traj->uniform_time_step == STEPPING_UNIFORM_TIME_STAMP) { + angle += 0.5 * traj->now_acceleration[i] * (traj->accelerate_time_step) * (traj->accelerate_time_step); + angle += traj->aim_velocity[i] * (time_step - traj->accelerate_time_step); + } else if (time_step <= 2 * traj->accelerate_time_step + traj->uniform_time_step) { + int decelerate_time_step = time_step - traj->accelerate_time_step - traj->uniform_time_step; + angle += 0.5 * traj->now_acceleration[i] * (traj->accelerate_time_step) * (traj->accelerate_time_step); + angle += traj->aim_velocity[i] * (traj->uniform_time_step); + angle += traj->aim_velocity[i] * decelerate_time_step + - 0.5 * traj->now_acceleration[i] * decelerate_time_step * decelerate_time_step; + } + aimAngles[i] = angle; + } +} + +void TrapezoidalTrajectory::getAngleForChecking(float *aimAngles) +{ + if (nowTrajectoryIndex_ < 0) { + return; + } + Trajectory* traj = &trajectoryHistory_[nowTrajectoryIndex_]; + getAngleForCheckingInner(traj, ARM_FOLLOWING_CHECKING_STEP * 2, aimAngles); +} + +void TrapezoidalTrajectory::getAngleForStarting(float *aimAngles) +{ + if (nowTrajectoryIndex_ < 0) { + return; + } + Trajectory* traj = &trajectoryHistory_[nowTrajectoryIndex_]; + getAngleForCheckingInner(traj, ARM_FOLLOWING_CHECKING_STEP, aimAngles); +} + +void TrapezoidalTrajectory::stopTrajectory() +{ + if (nowTrajectoryIndex_ < 0) { + return; + } + Trajectory* traj = &trajectoryHistory_[nowTrajectoryIndex_]; + int formerPoseSteppingUniformTimeStep = traj->uniform_time_step; + if (traj->current_time_step < traj->accelerate_time_step) { + traj->accelerate_time_step = traj->current_time_step; + traj->uniform_time_step = 0; + } else if (traj->uniform_time_step == STEPPING_UNIFORM_TIME_STAMP || + traj->current_time_step < traj->accelerate_time_step + traj->uniform_time_step) { + traj->uniform_time_step = traj->current_time_step - traj->accelerate_time_step; + } + traj->stopTime = traj->startTime + ARM_FOLLOWING_PERIOD * (traj->accelerate_time_step * 2 + traj->uniform_time_step); + for (int i = 0; i < USED_ARM_DOF; ++i) { + if (traj->goalType == GOAL_TYPE_POSE_STEPPING) { + traj->now_acceleration[i] = traj->aim_velocity[i] / traj->accelerate_time_step; + traj->endAngles[i] = traj->endAngles[i] + - traj->aim_velocity[i] * (formerPoseSteppingUniformTimeStep - traj->uniform_time_step); + traj->endAngles[i] += 0.5 * traj->now_acceleration[i] * traj->accelerate_time_step * traj->accelerate_time_step; + } else { + traj->endAngles[i] = traj->startAngles[i] + traj->aim_velocity[i] * (traj->uniform_time_step + traj->accelerate_time_step); + } + } + if (traj->goalType == GOAL_TYPE_POSE_STEPPING) { + traj->goalType = GOAL_TYPE_MOVING; + } +} + +int TrapezoidalTrajectory::continuePoseSteppingTrajectory(float *nowAngles, float *aimAngles) +{ + // Update the aimAngles based on the computed trajectory + Trajectory* newTrajectory = &trajectoryHistory_[nowTrajectoryIndex_]; + float angle_diff[USED_ARM_DOF]; + float max_angle = 0.0; + float max_velocity = 0.0; + int fastestIndex = 0; + for (int i = 0; i < USED_ARM_DOF; ++i) { + newTrajectory->endAngles[i] = aimAngles[i]; + angle_diff[i] = newTrajectory->endAngles[i] - nowAngles[i]; + float abs_diff = fabs(angle_diff[i]); + if (abs_diff > max_angle) { + max_angle = abs_diff; + fastestIndex = i; + } + } + max_velocity = fabs(newTrajectory->aim_velocity[fastestIndex]); + if (max_velocity * ARM_FOLLOWING_CHECKING_STEP * 2 >= max_angle) { + max_velocity = max_angle / (ARM_FOLLOWING_CHECKING_STEP * 2); + } + for (int i = 0; i < USED_ARM_DOF; ++i) { + if (max_angle < 0.0001) { + newTrajectory->aim_velocity[i] = 0; + } else { + newTrajectory->aim_velocity[i] = max_velocity * angle_diff[i] / max_angle; + } + } + newTrajectory->uniform_time_step += max_angle / max_velocity; + return 0; +} + +int TrapezoidalTrajectory::updatePoseSteppingTrajectory(float *aimAngles) +{ + Trajectory* newTrajectory = &trajectoryHistory_[nowTrajectoryIndex_]; + newTrajectory->current_time_step++; + if (newTrajectory->current_time_step < newTrajectory->accelerate_time_step) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + float v = newTrajectory->now_acceleration[i] * newTrajectory->current_time_step; + aimAngles[i] += v; + } + } else if (newTrajectory->current_time_step < newTrajectory->accelerate_time_step + newTrajectory->uniform_time_step) { + for (int i = 0; i < USED_ARM_DOF; ++i) { + aimAngles[i] += newTrajectory->aim_velocity[i]; + } + } else { + for (int i = 0; i < USED_ARM_DOF; ++i) { + aimAngles[i] += newTrajectory->aim_velocity[i]; + } + return TRAJECTORY_COMPELETE; + } + return TRAJECTORY_ONGOING; +} \ No newline at end of file diff --git a/rm_arm_control/urdf/FHrobot.csv b/rm_arm_control/urdf/FHrobot.csv new file mode 100644 index 0000000..8063e93 --- /dev/null +++ b/rm_arm_control/urdf/FHrobot.csv @@ -0,0 +1,31 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +base_link,-0.0205378231410598,-9.61865184431513E-05,0.0254107840927397,0,0,0,13.1017676019814,0.0621964572593383,-0.000154845566537037,0.00096044051222667,0.0984698574024698,0.000133407208946461,0.132724324840127,0,0,0,0,0,0,package://FHrobot/meshes/base_link.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://FHrobot/meshes/base_link.STL,,下身装配-1/髋部模组-1/右前髋模组-4/髋模组安装件-改-1;下身装配-1/髋部模组-1/DS-CLS9-FETC-2I(2A)-4;下身装配-1/髋部模组-1/髋部顶板-1;下身装配-1/髋部模组-1/RH-25非抱闸-2;下身装配-1/髋部模组-1/左前髋模组-1/髋模组安装件-改-1;下身装配-1/髋部模组-1/左前髋模组-1/髋部外摆芯轴-1;下身装配-1/髋部模组-1/右前髋模组-4/髋部外摆芯轴-1;下身装配-1/髋部模组-1/KS104-V100_CN超-2;下身装配-1/髋部模组-1/KS104-V100_CN超-1;下身装配-1/髋部模组-1/电池仓-1;下身装配-1/髋部模组-1/48V30Ah格瑞普-1;下身装配-1/髋部模组-1/基座前板-1;下身装配-1/髋部模组-1/SD-1000-1;下身装配-1/髋部模组-1/左前髋模组-1/X12-320-2;下身装配-1/髋部模组-1/正极汇流排-5pin-2/正极汇流排-5pin-2;下身装配-1/髋部模组-1/负极汇流排-1/负极汇流排-5pin-1;下身装配-1/髋部模组-1/电池接插件安装件-1;下身装配-1/髋部模组-1/3代宏致插头板-Z-350A-1;下身装配-1/髋部模组-1/右前髋模组-4/X12-320-2;下身装配-1/髋部模组-1/基座后板-1,base_link,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +left_behind_hip_link,-0.0707080720829581,0.0349108332402046,-0.194268849359242,0,0,0,1.67018071832031,0.019242511335113,0.000237007853026257,-0.00663178365847534,0.0220548947993352,0.000651174186468675,0.00343560973611031,0,0,0,0,0,0,package://FHrobot/meshes/left_behind_hip_link.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://FHrobot/meshes/left_behind_hip_link.STL,,下身装配-1/后腿模组-1/后大腿-1;下身装配-1/后腿模组-1/23E2225R4-350SSSB-KPL40G-180-2;下身装配-1/后腿模组-1/MGN15H1R300Z0C导轨-2;下身装配-1/后腿模组-1/MGN15H1R300Z0C导轨-1,left_behind_hip,A_left_behind_hip,left_behind_hip_joint,revolute,-0.1135,0.187,0.084,0,0,0,base_link,0,-1,0,120,1,-1,1,,,,,,,, +left_behind_leg_link,-0.0711857335259974,0.00455626330977332,-0.195672939343181,0,0,0,1.68458793046072,0.0127556330926767,7.33294579526056E-05,-0.00403123874160748,0.0155086686553562,0.000200905711305125,0.00312629851068732,0,0,0,0,0,0,package://FHrobot/meshes/left_behind_leg_link.STL,0.411764705882353,0.411764705882353,0.411764705882353,1,0,0,0,0,0,0,package://FHrobot/meshes/left_behind_leg_link.STL,,下身装配-1/后腿模组-1/HC01E1.H2.WL2.02-后小腿-1;下身装配-1/后腿模组-1/后腿动力块-1;下身装配-1/后腿模组-1/MGN15H1R240Z0C滑块-1;下身装配-1/后腿模组-1/MGN15H1R240Z0C滑块-2;下身装配-1/后腿模组-1/CP.BM.000081-P1010B-111 减速电机(外发)--1;下身装配-1/后腿模组-1/驱动电机外罩-1;下身装配-1/后腿模组-1/螺母-1,left_behind_leg,A_left_behind_leg,left_behind_leg_joint,prismatic,-0.12231,0.044,-0.33603,0,0,0,left_behind_hip_link,-0.34202,0,-0.93969,60,0.3,0,0.5,,,,,,,, +left_behind_wheel_link,0,0.0142488445904861,1.11022302462516E-16,0,0,0,0.836341270555146,0.00226461322979517,-3.86094891421227E-18,-1.87556603253604E-19,0.00431283295885682,-2.42351519738634E-18,0.00226461322979516,0,0,0,0,0,0,package://FHrobot/meshes/left_behind_wheel_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://FHrobot/meshes/left_behind_wheel_link.STL,,下身装配-1/后腿模组-1/驱动轮180-3,left_behind_wheel,A_left_behind_wheel,left_behind_wheel_joint,revolute,-0.13325,0.0285,-0.3661,0,0,0,left_behind_leg_link,0,1,0,80,1,-100000,100000,,,,,,,, +right_behind_hip_link,-0.0707080839298932,-0.0349108331105711,-0.194268845474145,0,0,0,1.67018070853773,0.0192425122713225,-0.000237008151644226,-0.00663178249937412,0.0220548947058849,-0.000651174096999173,0.00343560868904593,0,0,0,0,0,0,package://FHrobot/meshes/right_behind_hip_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_behind_hip_link.STL,,下身装配-1/后腿模组-2/23E2225R4-350SSSB-KPL40G-180-2;下身装配-1/后腿模组-2/MGN15H1R300Z0C导轨-1;下身装配-1/后腿模组-2/MGN15H1R300Z0C导轨-2;下身装配-1/后腿模组-2/后大腿-1,right_behind_hip,A_right_behind_hip,right_behind_hip_joint,revolute,-0.1135,-0.187,0.084,0,0,0,base_link,0,1,0,120,1,-1,1,,,,,,,, +right_behind_leg_link,-0.0712447041820832,-0.00455626331723741,-0.195651475077735,0,0,0,1.68458792989724,0.0127480753467506,-7.29675522814529E-05,-0.00404119223778022,0.0155099750927718,-0.00020103947318265,0.00313516270489064,0,0,0,0,0,0,package://FHrobot/meshes/right_behind_leg_link.STL,0.545098039215686,0.615686274509804,0.858823529411765,1,0,0,0,0,0,0,package://FHrobot/meshes/right_behind_leg_link.STL,,下身装配-1/后腿模组-2/后腿动力块-1;下身装配-1/后腿模组-2/MGN15H1R240Z0C滑块-1;下身装配-1/后腿模组-2/MGN15H1R240Z0C滑块-2;下身装配-1/后腿模组-2/HC01E1.H2.WL2.02-后小腿-1;下身装配-1/后腿模组-2/CP.BM.000081-P1010B-111 减速电机(外发)--1;下身装配-1/后腿模组-2/驱动电机外罩-1;下身装配-1/后腿模组-2/螺母-1,right_behind_leg,A_right_behind_leg,right_behind_leg_joint,prismatic,-0.12231,-0.044,-0.33603,0,0,0,right_behind_hip_link,-0.34202,0,-0.93969,60,0.3,0,0.5,,,,,,,, +right_behind_wheel_link,1.11022302462516E-16,-0.0142488445904863,1.11022302462516E-16,0,0,0,0.836341270555146,0.00226461322979519,-4.37853796162416E-18,-2.48392769899829E-19,0.00431283295885682,1.94666730785686E-18,0.00226461322979519,0,0,0,0,0,0,package://FHrobot/meshes/right_behind_wheel_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://FHrobot/meshes/right_behind_wheel_link.STL,,下身装配-1/后腿模组-2/驱动轮180-3,right_behind_wheel,A_right_behind_wheel,right_behind_wheel_joint,revolute,-0.13325,-0.0285,-0.3661,0,0,0,right_behind_leg_link,0,-1,0,80,1,-100000,100000,,,,,,,, +body_link,-0.00263929956213401,0.0125198182992841,0.056091427928817,0,0,0,2.73918994680822,0.00850260018538599,1.56151930687314E-05,2.74601060299229E-05,0.00617878425027525,-0.00137286213684896,0.0085452089662433,0,0,0,0,0,0,package://FHrobot/meshes/body_link.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://FHrobot/meshes/body_link.STL,,上半身-20250907-1/躯干模块-20250820-1/腰部关节支撑4-1;上半身-20250907-1/躯干模块-20250820-1/腰部关节支撑2-1;上半身-20250907-1/躯干模块-20250820-1/erob110h××i-xx-18ex_v4_mc2b.dx.xx-1;上半身-20250907-1/躯干模块-20250820-1/03轴壳前-1;上半身-20250907-1/躯干模块-20250820-1/腰部限位1-1;上半身-20250907-1/躯干模块-20250820-1/腰部限位1-2,body_link,A_body_link,body_joint,revolute,0,0,0.1595,0,0,0,base_link,0,0,1,120,1,-1.5,1.5,,,,,,,, +body_2_link,0.00996920182001421,-0.113780557271402,0.27167355481843,0,0,0,16.222486126677,0.247002392142746,0.000315128514460768,-0.00205305076755159,0.202261283610442,0.000938072746687644,0.121688618847805,0,0,0,0,0,0,package://FHrobot/meshes/body_2_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/body_2_link.STL,,上半身-20250907-1/躯干模块-20250820-1/劲臣科技PCB-ethercat分支器-1;上半身-20250907-1/躯干模块-20250820-1/485-HUB-1;上半身-20250907-1/躯干模块-20250820-1/RS485固定板-1;上半身-20250907-1/躯干模块-20250820-1/24V转12v电源-1;上半身-20250907-1/躯干模块-20250820-1/EtherCAT分支器固定板-1;上半身-20250907-1/躯干模块-20250820-1/NP-6123-L4-1;上半身-20250907-1/躯干模块-20250820-1/MXDY-200W-1;上半身-20250907-1/躯干模块-20250820-1/科大讯飞麦克风-1;上半身-20250907-1/躯干模块-20250820-1/语音模块固定-1;上半身-20250907-1/躯干模块-20250820-1/绿联USB-hub固定-1;上半身-20250907-1/躯干模块-20250820-1/左臂--1-2/睿尔曼信号线电源线-2;上半身-20250907-1/躯干模块-20250820-1/左臂--1-2/睿尔曼信号线电源线-1;上半身-20250907-1/躯干模块-20250820-1/躯干结构件4-1;上半身-20250907-1/躯干模块-20250820-1/躯干结构件3-2;上半身-20250907-1/躯干模块-20250820-1/绿联总控7口USBhub-1;上半身-20250907-1/躯干模块-20250820-1/手臂固定板-2;上半身-20250907-1/躯干模块-20250820-1/手臂固定板-1;上半身-20250907-1/躯干模块-20250820-1/上身按钮安装板-1;上半身-20250907-1/躯干模块-20250820-1/躯干竖板右侧-1;上半身-20250907-1/躯干模块-20250820-1/02后壳上-1;上半身-20250907-1/躯干模块-20250820-1/躯干前壳-1;上半身-20250907-1/躯干模块-20250820-1/腰部关节支撑3-1;上半身-20250907-1/躯干模块-20250820-1/躯干底板2-1;上半身-20250907-1/躯干模块-20250820-1/腰部轴3-1;上半身-20250907-1/躯干模块-20250820-1/NP6133固定板-1;上半身-20250907-1/躯干模块-20250820-1/左臂--1-1/睿尔曼信号线电源线-1;上半身-20250907-1/躯干模块-20250820-1/躯干竖板1-1;上半身-20250907-1/头部模块-20250901-1/脖子底板-第二版-1;上半身-20250907-1/躯干模块-20250820-1/左臂--1-1/关节--1-1;上半身-20250907-1/躯干模块-20250820-1/GB╱T 825-1988[吊环螺钉M8]-1;上半身-20250907-1/躯干模块-20250820-1/GB╱T 825-1988[吊环螺钉M8]-2,body_2_link,A_body_2_link,body_2_joint,revolute,-0.00074647,0.105,0.094,0,0,0,body_link,-0.0071092,0.99997,0,120,1,-0.5,0.5,,,,,,,, +head_link,5.45840627699192E-07,-7.4829077079445E-08,0.419571722857199,0,0,0,1452.2903727715,367.96311570062,0.0881129053260821,-2.03608765162285E-06,355.633873495802,1.71873986656022E-06,619.425510611837,0,0,0,0,0,0,package://FHrobot/meshes/head_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://FHrobot/meshes/head_link.STL,,上半身-20250907-1/头部模块-20250901-1/头部ID2装配体-1/头部ID202前壳-2;上半身-20250907-1/头部模块-20250901-1/Gemini 335L_20240318-1-2;上半身-20250907-1/头部模块-20250901-1/头部ID2装配体-1/头部ID203后壳-2;上半身-20250907-1/头部模块-20250901-1/头部框-3-1;上半身-20250907-1/头部模块-20250901-1/头部出线固定2-1;上半身-20250907-1/头部模块-20250901-1/脉塔X2-7-2;上半身-20250907-1/头部模块-20250901-1/mid360-1,head_link,A_head_link,head_joint,revolute,0.00074647,-0.105,0.537,0,0,0,body_2_link,0,0,1,10,1,-3.14,3.14,,,,,,,, +left_shoulder_link,-0.0215750512333122,0.065662134604277,2.05888208482108E-07,0,0,0,0.593542142722961,0.00117862475882049,0.000215593077572073,-5.148131954591E-09,0.000564354451514675,6.326543107061E-09,0.00126611479611715,0,0,0,0,0,0,package://FHrobot/meshes/left_shoulder_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_shoulder_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-2/关节--2-1,left_shoulder,A_left_shoulder,left_shoulder_joint,revolute,-0.00048698,0.068498,0.421,0,0,0,body_2_link,-0.0071092,0.99997,0,60,1,-1.5,1.5,,,,,,,, +left_arm_1_link,-0.0196731940589509,-0.000139368738221624,-0.152256757061078,0,0,0,0.864175973653755,0.00195282150460298,-7.06466836133975E-07,-0.000421618407120519,0.00205271879438062,-2.98213967724978E-06,0.000632536755321906,0,0,0,0,0,0,package://FHrobot/meshes/left_arm_1_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_arm_1_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-2/关节--3-2,left_arm_1,A_left_arm_1,left_arm_1_joint,revolute,0.012824,0.091094,0,0,0,0,left_shoulder_link,0.99997,0.0071092,0,60,1,-1.5,1.5,,,,,,,, +left_arm_2_link,-0.00266686769296298,-1.44536756317981E-05,-0.0595928481594618,0,0,0,0.289644058225621,0.00061417725335236,-1.97914856640995E-07,-0.000144604331758442,0.000637362607071379,-1.08550996512855E-06,0.000156488398200079,0,0,0,0,0,0,package://FHrobot/meshes/left_arm_2_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_arm_2_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-2/关节--4-1,left_arm_2,A_left_arm_2,left_arm_2_joint,revolute,-0.00053514,0,-0.256,0,0,0,left_arm_1_link,0.99997,0.0071092,0,60,1,-1.5,1.5,,,,,,,, +left_arm_3_link,-0.0180433024259728,-0.000128080756080895,-0.0599618414467747,0,0,0,0.239430988823185,0.000262736746987041,-1.67180224792151E-07,-4.42396775332355E-05,0.000285948588252907,-3.15927605811713E-07,0.000119899050391641,0,0,0,0,0,0,package://FHrobot/meshes/left_arm_3_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_arm_3_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-2/关节--5-1,left_arm_3,A_left_arm_3,left_arm_3_joint,revolute,-0.013236,-9.41E-05,-0.1285,0,0,0,left_arm_2_link,0,0,1,60,1,-3.14,3.14,,,,,,,, +left_arm_4_link,-0.00236789625803245,-1.25933165274206E-05,-0.0593817591198472,0,0,0,0.218795231349055,0.000334472220037392,-1.31236143559414E-07,-7.82384185721716E-05,0.000350530008524306,-5.87329264291948E-07,0.000104925416502353,0,0,0,0,0,0,package://FHrobot/meshes/left_arm_4_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_arm_4_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-2/关节--6-2,left_arm_4,A_left_arm_4,left_arm_4_joint,revolute,0.0094358,6.7083E-05,-0.0815,0,0,0,left_arm_3_link,0.99997,0.0071092,0,60,1,-1.5,1.5,,,,,,,, +left_wrist_link,0.000681380758623055,0.000449766271691632,-0.0147952980904526,0,0,0,0.0650358712344706,2.01554265885248E-05,1.42250530829564E-06,2.6865330456467E-08,1.90964564316425E-05,6.01991437360921E-09,3.1899692159194E-05,0,0,0,0,0,0,package://FHrobot/meshes/left_wrist_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_wrist_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-2/手腕---2,left_wrist,A_left_wrist,left_wrist_joint,revolute,-0.0097355,-6.809E-05,-0.1165,0,0,0,left_arm_4_link,0,0,-1,60,1,-3.14,3.14,,,,,,,, +right_shoulder_link,0.0215750516273929,-0.0656621158727069,1.68449794890613E-07,0,0,0,0.593541862011099,0.00117862484134581,0.000215593025871603,5.15678842854373E-09,0.000564354656118937,-6.22735317975621E-09,0.00126611462515893,0,0,0,0,0,0,package://FHrobot/meshes/right_shoulder_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_shoulder_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-1/关节--2-1,right_shoulder,A_right_shoulder,right_shoulder_joint,revolute,0.0019799,-0.27849,0.421,0,0,0,body_2_link,0.0071092,-0.99997,0,60,1,-1.5,1.5,,,,,,,, +right_arm_1_link,0.0196731924238126,0.000139364173582346,-0.152256778447643,0,0,0,0.864175834140852,0.00195282103807737,-7.06523985583904E-07,0.000421618230277501,0.00205271835946634,2.98234817263437E-06,0.000632536550781556,0,0,0,0,0,0,package://FHrobot/meshes/right_arm_1_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_arm_1_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-1/关节--3-2,right_arm_1,A_right_arm_1,right_arm_1_joint,revolute,-0.012824,-0.091094,0,0,0,0,right_shoulder_link,-0.99997,-0.0071092,0,60,1,-1.5,1.5,,,,,,,, +right_arm_2_link,0.0011668982309032,3.79162934593946E-06,-0.0595928462343879,0,0,0,0.289644006433552,0.000614177253347669,-1.97925827203084E-07,0.00014460429892374,0.000637362568736811,1.0855152784167E-06,0.000156488351532922,0,0,0,0,0,0,package://FHrobot/meshes/right_arm_2_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_arm_2_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-1/关节--4-1,right_arm_2,A_right_arm_2,right_arm_2_joint,revolute,0.0020351,1.4477E-05,-0.256,0,0,0,right_arm_1_link,-0.99997,-0.0071092,0,60,1,-1.5,1.5,,,,,,,, +right_arm_3_link,0.0180433036907632,0.00012808141448134,-0.0599618426608898,0,0,0,0.23943097940046,0.000262736735309649,-1.67174733494034E-07,4.42396678734598E-05,0.000285948568864451,3.15922385357831E-07,0.000119899037005012,0,0,0,0,0,0,package://FHrobot/meshes/right_arm_3_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_arm_3_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-1/关节--5-1,right_arm_3,A_right_arm_3,right_arm_3_joint,revolute,0.011736,8.3436E-05,-0.1285,0,0,0,right_arm_2_link,0,0,-1,60,1,-3.14,3.14,,,,,,,, +right_arm_4_link,0.00236789279985283,1.25952945493335E-05,-0.0593817589007529,0,0,0,0.21879523183536,0.00033447221767345,-1.31243084234095E-07,7.8238417465711E-05,0.000350530023020864,5.87328093883178E-07,0.000104925391711953,0,0,0,0,0,0,package://FHrobot/meshes/right_arm_4_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_arm_4_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-1/关节--6-2,right_arm_4,A_right_arm_4,right_arm_4_joint,revolute,-0.0094358,-6.7083E-05,-0.0815,0,0,0,right_arm_3_link,-0.99997,-0.0071092,0,60,1,-1.5,1.5,,,,,,,, +right_wrist_link,-0.000681381399737627,-0.000449766276256425,-0.0147952980607874,0,0,0,0.0650358712344382,2.01554265862145E-05,1.42250530805463E-06,-2.68648220023955E-08,1.90964564317584E-05,-6.01997204792059E-09,3.18996921616863E-05,0,0,0,0,0,0,package://FHrobot/meshes/right_wrist_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_wrist_link.STL,,上半身-20250907-1/躯干模块-20250820-1/左臂--1-1/手腕---2,right_wrist,A_right_wrist,right_wrist_joint,revolute,0.0097355,6.809E-05,-0.1165,0,0,0,right_arm_4_link,0,0,1,60,1,-3.14,3.14,,,,,,,, +left_front_roll_link,-0.00342961386275646,0.0174122322811494,-0.00050308685690538,0,0,0,1.07732174634592,0.00145708315569525,-0.000109118759573662,3.15617952067231E-06,0.00270943261603907,-1.43352998429783E-05,0.00221885026633298,0,0,0,0,0,0,package://FHrobot/meshes/left_front_roll_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_front_roll_link.STL,,下身装配-1/髋部模组-1/左前髋模组-1/X12-320-1;下身装配-1/髋部模组-1/左前髋模组-1/髋pitch模组安装件-1,left_front_roll,A_left_front_roll,left_front_roll_joint,revolute,0.1005,0.13,0.084,0,0,0,base_link,-1,0,0,120,1,0,0.175,,,,,,,, +left_front_hip_link,0.074050793227453,0.0741529531569444,-0.203420783048688,0,0,0,1.31272995912479,0.0202349848138959,-0.000194460602389144,0.00683546679399535,0.0235523843360919,0.000535482751167264,0.00394247258663016,0,0,0,0,0,0,package://FHrobot/meshes/left_front_hip_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_front_hip_link.STL,,膝关节模组外壳-1;下身装配-1/左前腿模组-5/X6-60E-1;前大腿外罩-1;下身装配-1/左前腿模组-5/前大腿-1,left_front_hip,A_left_front_hip,left_front_hip_joint,revolute,0,0,0,0,0,0,left_front_roll_link,0,1,0,120,1,-1,1,,,,,,,, +left_front_knee_link,0.0810965866623868,0.00453343582644863,-0.193768149584023,0,0,0,1.04303661988793,0.0107259148921607,0.000343803708006765,0.00353633084931868,0.0120399333062396,-0.000944593492183201,0.00279824093829573,0,0,0,0,0,0,package://FHrobot/meshes/left_front_knee_link.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://FHrobot/meshes/left_front_knee_link.STL,,下身装配-1/左前腿模组-5/前小腿-1;下身装配-1/左前腿模组-5/左前轮罩-1,left_front_knee,A_left_front_knee,left_front_knee_joint,revolute,0.13168,0.0945,-0.36178,0,0,0,left_front_hip_link,0,1,0,100,1,0,2,,,,,,,, +left_front_wheel_link,4.503668653566E-07,-0.0285000006367639,2.89726453717165E-07,0,0,0,0.789299282365244,0.00161691380083824,4.72046704944816E-10,4.51514966737E-09,0.00294570206605477,-3.91441758430146E-10,0.00161690908867884,0,0,0,0,0,0,package://FHrobot/meshes/left_front_wheel_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/left_front_wheel_link.STL,,下身装配-1/左前腿模组-5/R2-1801-XX-1,left_front_wheel,A_left_front_wheel,left_front_wheel_joint,revolute,0.12381,0.0095,-0.34017,0,0,0,left_front_knee_link,0,1,0,80,1,-100000,100000,,,,,,,, +right_front_roll_link,-0.00345998879261027,-0.017412232281147,0.000495329152665938,0,0,0,1.07732174634606,0.00145740892081969,0.00010998944826947,-2.19277236355822E-06,0.00270943261603792,-1.42840101412956E-05,0.00221852450120745,0,0,0,0,0,0,package://FHrobot/meshes/right_front_roll_link.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://FHrobot/meshes/right_front_roll_link.STL,,下身装配-1/髋部模组-1/右前髋模组-4/髋pitch模组安装件-1;下身装配-1/髋部模组-1/右前髋模组-4/X12-320-1,right_front_roll,A_right_front_roll,right_front_roll_joint,revolute,0.1005,-0.13,0.084,0,0,0,base_link,-1,0,0,120,1,0,0.175,,,,,,,, +right_front_hip_link,0.074030157256486,-0.0742482782915145,-0.203428290517255,0,0,0,1.31272988648635,0.0202349363980353,0.0001952358325651,0.00683552907176235,0.0235523898342542,-0.000535201364227481,0.00394252624941688,0,0,0,0,0,0,package://FHrobot/meshes/right_front_hip_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_front_hip_link.STL,,下身装配-1/右前腿模组-7/前大腿外罩-1;下身装配-1/右前腿模组-7/膝关节模组外壳-2;下身装配-1/右前腿模组-7/X6-60E-1;下身装配-1/右前腿模组-7/前大腿-1,right_front_hip,A_right_front_hip,right_front_hip_joint,revolute,0,0,0,0,0,0,right_front_roll_link,0,-1,0,120,1,-1,1,,,,,,,, +right_front_knee_link,0.0860177735131513,0.00736862965660176,-0.20036198564181,0,0,0,1.13692922676896,0.0109703937799717,-0.000348044131256059,0.00359600066492126,0.0123331802632592,0.000953909458343272,0.00307591661694504,0,0,0,0,0,0,package://FHrobot/meshes/right_front_knee_link.STL,0.898039215686275,0.917647058823529,0.929411764705882,1,0,0,0,0,0,0,package://FHrobot/meshes/right_front_knee_link.STL,,下身装配-1/右前腿模组-7/前小腿-1;下身装配-1/右前腿模组-7/右前轮罩-1,right_front_knee,A_right_front_knee,right_front_knee_joint,revolute,0.13168,-0.0945,-0.36178,0,0,0,right_front_hip_link,0,-1,0,100,1,0,2,,,,,,,, +right_front_wheel_link,-5.14743496438097E-07,0.0242553310792356,1.45149822605717E-07,0,0,0,0.789294886388936,0.00161691175368426,3.36419846114913E-10,-2.41988431499183E-09,0.00294569452705004,5.13093407213974E-10,0.00161690277252843,0,0,0,0,0,0,package://FHrobot/meshes/right_front_wheel_link.STL,1,1,1,1,0,0,0,0,0,0,package://FHrobot/meshes/right_front_wheel_link.STL,,下身装配-1/右前腿模组-7/R2-1801-XX-1,right_front_wheel,A_right_front_wheel,right_front_wheel_joint,revolute,0.12381,-0.0052554,-0.34017,0,0,0,right_front_knee_link,0,-1,0,80,1,-100000,100000,,,,,,,, diff --git a/rm_arm_control/urdf/FHrobot.urdf b/rm_arm_control/urdf/FHrobot.urdf new file mode 100644 index 0000000..18b425a --- /dev/null +++ b/rm_arm_control/urdf/FHrobot.urdf @@ -0,0 +1,1803 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rm_arm_control/urdf/leftarm.urdf b/rm_arm_control/urdf/leftarm.urdf new file mode 100644 index 0000000..d86ed4b --- /dev/null +++ b/rm_arm_control/urdf/leftarm.urdf @@ -0,0 +1,402 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rm_arm_control/urdf/rightarm.urdf b/rm_arm_control/urdf/rightarm.urdf new file mode 100644 index 0000000..43ac99b --- /dev/null +++ b/rm_arm_control/urdf/rightarm.urdf @@ -0,0 +1,402 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rm_arm_control/urdf/rm_65_b.urdf b/rm_arm_control/urdf/rm_65_b.urdf new file mode 100644 index 0000000..be47ea5 --- /dev/null +++ b/rm_arm_control/urdf/rm_65_b.urdf @@ -0,0 +1,827 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rm_arm_control/urdf/rm_65_b_description.csv b/rm_arm_control/urdf/rm_65_b_description.csv new file mode 100644 index 0000000..d8a1f55 --- /dev/null +++ b/rm_arm_control/urdf/rm_65_b_description.csv @@ -0,0 +1,8 @@ +Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity +base_link,-0.00043233,-3.2765E-05,0.059942,0,0,0,0.84108,0.0017261,2.4864E-06,-3.6752E-05,0.0017099,1.7199E-06,0.00090404,0,0,0,0,0,0,package://arm_description/meshes/base_link.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_description/meshes/base_link.STL,,____1-1,baselink,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, +Link1,1.4691E-07,0.021109,-0.025186,0,0,0,0.59356,0.0012661,-1.2313E-08,-1.0057E-08,0.0011817,-0.00021122,0.00056135,0,0,0,0,0,0,package://arm_description/meshes/Link1.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_description/meshes/Link1.STL,,____2-1,Link1,axis1,joint1,revolute,0,0,0.2405,0,0,0,base_link,0,0,-1,100,1,-3.107,3.107,,,,,,,, +Link2,0.15226,4.2545E-07,-0.0062026,0,0,0,0.86418,0.00063253,-8.795E-09,0.00042163,0.0020527,2.3725E-09,0.0019528,0,0,0,0,0,0,package://arm_description/meshes/Link2.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_description/meshes/Link2.STL,,____3-1;____4-1,Link2,axis2,joint2,revolute,0,0,0,1.5708,-1.5708,0,Link1,0,0,1,100,1,-2.269,2.269,,,,,,,, +Link3,4.7938E-06,-0.059593,0.010569,0,0,0,0.28965,0.00063737,-5.9726E-08,-3.3299E-08,0.00015649,-0.00014461,0.00061418,0,0,0,0,0,0,package://arm_description/meshes/Link3.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_description/meshes/Link3.STL,,____5-1,Link3,axis3,joint3,revolute,0.256,0,0,0,0,1.5708,Link2,0,0,1,100,1,-2.356,2.356,,,,,,,, +Link4,1.0293E-06,-0.018042,-0.021539,0,0,0,0.23942,0.00028594,2.854E-09,-1.9592E-09,0.00026273,4.4237E-05,0.00011989,0,0,0,0,0,0,package://arm_description/meshes/Link4.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_description/meshes/Link4.STL,,____6-1,Link4,axis4,joint4,revolute,0,-0.21,0,1.5708,0,0,Link3,0,0,1,100,1,-3.107,3.107,,,,,,,, +Link5,3.4528E-06,-0.059382,0.0073678,0,0,0,0.21879,0.00035053,-3.165E-08,-1.7434E-08,0.00010492,-7.824E-05,0.00033447,0,0,0,0,0,0,package://arm_description/meshes/Link5.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_description/meshes/Link5.STL,,____7-1,Link5,axis5,joint5,revolute,0,0,0,-1.5708,0,0,Link4,0,0,1,100,1,-2.234,2.234,,,,,,,, +Link6,0.00081643,1.3288E-05,-0.012705,0,0,0,0.065035,2.1143E-05,-2.2878E-08,-2.5601E-08,1.811E-05,-1.0178E-08,3.19E-05,0,0,0,0,0,0,package://arm_description/meshes/Link6.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_description/meshes/Link6.STL,,__________ ______-1,Link6,axis6,joint6,revolute,0,-0.144,0,1.5708,0,0,Link5,0,0,1,100,1,-6.283,6.283,,,,,,,, diff --git a/rm_arm_control/urdf/rm_65_b_description.urdf b/rm_arm_control/urdf/rm_65_b_description.urdf new file mode 100644 index 0000000..f6b820a --- /dev/null +++ b/rm_arm_control/urdf/rm_65_b_description.urdf @@ -0,0 +1,827 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/rm_arm_control/urdf/robot.urdf b/rm_arm_control/urdf/robot.urdf new file mode 100644 index 0000000..6abf288 --- /dev/null +++ b/rm_arm_control/urdf/robot.urdf @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + +