修改sleep

This commit is contained in:
zj
2025-10-30 17:32:20 +08:00
parent 1b37132764
commit 95a6d6de9d
13 changed files with 1334 additions and 418 deletions

View File

@@ -0,0 +1,48 @@
cmake_minimum_required(VERSION 3.8)
project(create_robot_describer)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
add_compile_options(-g)
#set(CMAKE_BUILD_TYPE Release)
set(CGAL_DO_NOT_WARN_ABOUT_CMAKE_BUILD_TYPE TRUE)
set(CGAL_DATA_DIR ".")
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(gjk_interface REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(CGAL REQUIRED)
find_package(moveit_ros_planning_interface REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
include_directories(
include
${CMAKE_CURRENT_SOURCE_DIR}/../include
${EIGEN3_INCLUDE_DIRS} # 引入Eigen3的头文件路径
)
# 设置源文件
set(SOURCES
src/create_robot_describe.cpp
)
# 添加可执行文件
add_executable(create_robot_describer ${SOURCES})
ament_target_dependencies(create_robot_describer
gjk_interface
moveit_ros_planning_interface
)
target_link_libraries(create_robot_describer CGAL::CGAL)
install(TARGETS
create_robot_describer
DESTINATION lib/${PROJECT_NAME})
ament_package()

View File

@@ -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.

View File

@@ -0,0 +1,66 @@
#ifndef CREATE_ROBOT_DESCRIBE_HPP
#define CREATE_ROBOT_DESCRIBE_HPP
#include <string>
#include <vector>
#include <memory>
#include <map>
#include <moveit/collision_detection_bullet/collision_detector_allocator_bullet.h>
#include "gjk_interface.hpp"
struct JointsModel {
std::string name; // 关节名称
int type; // 关节类型
int parent_link; // 父连杆
int child_link; // 子连杆
Eigen::Vector3d axis; // 关节轴
Eigen::Vector3d nextLinkOffset; // 下一个连杆关于关节原点偏移
Eigen::Quaterniond rotation; // 关节旋转
double limit_lower;
double limit_upper;
double limit_v;
double limit_e;
};
struct CollisionModel {
std::string link_name; // 所属链接名称
std::string geometry_type; // 几何类型
std::string mesh_filename; // mesh文件路径如STL
std::vector<OBB> obbModelList; // 网格边界盒 [min_x, max_x, min_y, max_y, min_z, max_z]
std::vector<JointsModel> joint_list;
std::vector<int> obbLinkIndexList; // 网格边界盒所属链接索引
int joint_count;
int link_index;
int parent_link_index;
Eigen::Quaterniond rotation; // 链接旋转
Eigen::Vector3d offset; // 链接偏移
};
class RobotDescription
{
public:
RobotDescription(const std::string &urdf, const std::string &srdf);
~RobotDescription();
// 其他成员函数和变量
private:
int InitJointModel();
int InitJoint(const urdf::Model &urdf_model);
int GetMeshLinkdimensions(const std::string& filename, CollisionModel& col_struct);
int InitCollisionStructureList(const urdf::Model &urdf_model);
void UpdatePolyhedrons();
int InitLinkCollisionDetectMatrix(const std::string& srdf_str);
std::vector<CollisionModel> collision_structures_;
std::vector<JointsModel> jointMap_;
std::map<std::string, int> linkCollisionMap_;
int rootLinkIndex_;
int maxObbCnt;
bool *g_linkCollisionDetectMatrix;
};
#endif // CREATE_ROBOT_DESCRIBE_HPP

View File

@@ -0,0 +1,17 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>create_robot_describer</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="zhengjie@hivecore.cn">zj</maintainer>
<license>Apache-2.0</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>gjk_interface</depend>
<exec_depend>moveit_ros_planning_interface</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,492 @@
#include <fstream>
#include <string>
#include <stdexcept> // 用于抛出异常
#include <filesystem>
#include <iostream>
#include <moveit/robot_model/robot_model.h>
#include <CGAL/optimal_bounding_box.h>
#include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
#include <create_robot_describe.hpp>
#define UNUSED(x) (void)(x)
typedef CGAL::Exact_predicates_inexact_constructions_kernel CgalK;
typedef CgalK::Point_3 CgalPoint;
namespace fs = std::filesystem;
using namespace Eigen;
int RobotDescription::InitJointModel()
{
int linkIndex = rootLinkIndex_;
CollisionModel *colStruct = &collision_structures_[linkIndex];
std::vector<JointsModel *> jointList;
int index = 0;
int maxJointCount = 0;
Quaterniond rotationAll = Quaterniond::Identity();
while (colStruct->joint_count > 0 || index < maxJointCount) {
for (int i = 0; i < colStruct->joint_count; i++) {
jointList.push_back(&colStruct->joint_list[i]);
maxJointCount++;
printf("链接 %s 包含关节 %s, 原offset: (%.4f, %.4f, %.4f)\n", colStruct->link_name.c_str(), colStruct->joint_list[i].name.c_str(),
colStruct->joint_list[i].nextLinkOffset.x(),
colStruct->joint_list[i].nextLinkOffset.y(),
colStruct->joint_list[i].nextLinkOffset.z());
colStruct->joint_list[i].rotation = rotationAll * colStruct->joint_list[i].rotation;
colStruct->joint_list[i].axis = colStruct->joint_list[i].rotation * colStruct->joint_list[i].axis;
colStruct->joint_list[i].nextLinkOffset = rotationAll * colStruct->joint_list[i].nextLinkOffset;
printf("更新后关节 %s 旋转四元数: (%.4f, %.4f, %.4f, %.4f), 轴向: (%.4f, %.4f, %.4f), 偏移: (%.4f, %.4f, %.4f)\n",
colStruct->joint_list[i].name.c_str(),
colStruct->joint_list[i].rotation.w(),
colStruct->joint_list[i].rotation.x(),
colStruct->joint_list[i].rotation.y(),
colStruct->joint_list[i].rotation.z(),
colStruct->joint_list[i].axis.x(),
colStruct->joint_list[i].axis.y(),
colStruct->joint_list[i].axis.z(),
colStruct->joint_list[i].nextLinkOffset.x(),
colStruct->joint_list[i].nextLinkOffset.y(),
colStruct->joint_list[i].nextLinkOffset.z());
}
JointsModel *jointInfo = jointList[index];
rotationAll = jointInfo->rotation;
index++;
linkIndex = jointInfo->child_link;
colStruct = &collision_structures_[linkIndex];
for (size_t i = 0; i < colStruct->obbModelList.size(); i++) {
colStruct->obbModelList[i] = gjk_interface::updateOBBFromPoints(colStruct->obbModelList[i],
Vector3d::Zero(),
rotationAll);
}
}
return 0;
}
int RobotDescription::InitJoint(const urdf::Model &urdf_model)
{
for (const auto& joint_pair : urdf_model.joints_) {
urdf::JointConstSharedPtr joint = joint_pair.second;
JointsModel joint_info;
joint_info.name = joint->name;
joint_info.type = joint->type;
joint_info.parent_link = -1;
joint_info.child_link = -1;
if (joint->parent_link_name != "") {
if (linkCollisionMap_.find(joint->parent_link_name) != linkCollisionMap_.end()) {
joint_info.parent_link = linkCollisionMap_[joint->parent_link_name];
} else {
printf("Joint %s 的父链接 %s 未找到!", joint->name.c_str(), joint->parent_link_name.c_str());
return -1;
}
}
if (joint->child_link_name != "") {
if (linkCollisionMap_.find(joint->child_link_name) != linkCollisionMap_.end()) {
joint_info.child_link = linkCollisionMap_[joint->child_link_name];
} else {
printf("Joint %s 的子链接 %s 未找到!", joint->name.c_str(), joint->child_link_name.c_str());
return -1;
}
}
joint_info.nextLinkOffset = 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);
joint_info.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->type != urdf::Joint::FIXED) {
joint_info.axis = Vector3d(joint->axis.x, joint->axis.y, joint->axis.z);
if (joint->limits != NULL) {
joint_info.limit_lower = joint->limits->lower;
joint_info.limit_upper = joint->limits->upper;
joint_info.limit_v = joint->limits->velocity;
joint_info.limit_e = joint->limits->effort;
}
} else {
joint_info.axis = Vector3d::Zero();
joint_info.limit_lower = 0.0;
joint_info.limit_upper = 0.0;
joint_info.limit_v = 0.0;
joint_info.limit_e = 0.0;
}
jointMap_.push_back(joint_info);
CollisionModel *parentColStruct = &collision_structures_[joint_info.parent_link];
parentColStruct->joint_list.push_back(joint_info);
parentColStruct->joint_count++;
CollisionModel *childColStruct = &collision_structures_[joint_info.child_link];
childColStruct->parent_link_index = joint_info.parent_link;
}
InitJointModel();
return 0;
}
int RobotDescription::GetMeshLinkdimensions(const std::string& filename, CollisionModel& col_struct)
{
/*shapes::Mesh* mesh = shapes::createMeshFromResource(filename);
if (!mesh) {
printf("无法加载网格文件: %s\n", filename.c_str());
return false;
}
std::vector<Eigen::Vector3d> eigen_points;
std::vector<CgalPoint> points;
for (unsigned int i = 0; i < mesh->vertex_count; ++i) {
points.emplace_back(mesh->vertices[3*i], mesh->vertices[3*i + 1], mesh->vertices[3*i + 2]);
}
std::array<CgalPoint, 8> obb_points;
CGAL::oriented_bounding_box(points, obb_points, CGAL::parameters::use_convex_hull(true));
printf("计算%s得到的 OBB 顶点:\n", col_struct.link_name.c_str());
for (const auto& pt : obb_points) {
eigen_points.push_back(Eigen::Vector3d(pt.x(), pt.y(), pt.z()));
printf("(%.4f, %.4f, %.4f)\n", pt.x(), pt.y(), pt.z());
}*/
UNUSED(filename);
static std::map<std::string, std::array<Vector3d, 8>> pointMap = {
{"LeftLink1",
{Vector3d(0.0411, 0.0456, -0.1191), Vector3d(-0.0409, 0.0458, -0.1191), Vector3d(-0.0411, -0.0444, -0.1013), Vector3d(0.0409, -0.0446, -0.1013), Vector3d(0.0410, -0.0137, 0.0545), Vector3d(0.0412, 0.0765, 0.0366), Vector3d(-0.0408, 0.0767, 0.0366), Vector3d(-0.0410, -0.0135, 0.0545)}},
{"LeftLink2",
{Vector3d(0.2879, 0.0332, -0.0733), Vector3d(-0.0475, 0.0417, -0.0150), Vector3d(-0.0496, -0.0393, -0.0149), Vector3d(0.2858, -0.0478, -0.0732), Vector3d(0.3004, -0.0481, 0.0110), Vector3d(0.3025, 0.0329, 0.0109), Vector3d(-0.0329, 0.0414, 0.0691), Vector3d(-0.0349, -0.0396, 0.0692)}},
{"LeftLink3",
{Vector3d(0.0464, 0.0342, 0.0241), Vector3d(-0.0012, 0.0428, -0.0180), Vector3d(-0.0025, -0.1243, -0.0505), Vector3d(0.0451, -0.1329, -0.0084), Vector3d(0.0019, -0.1416, 0.0386), Vector3d(0.0032, 0.0254, 0.0710), Vector3d(-0.0443, 0.0340, 0.0289), Vector3d(-0.0456, -0.1331, -0.0036)}},
{"LeftLink4",
{Vector3d(0.0286, 0.0314, -0.0811), Vector3d(-0.0294, 0.0307, -0.0811), Vector3d(-0.0285, -0.0395, -0.0933), Vector3d(0.0295, -0.0388, -0.0933), Vector3d(0.0298, -0.0592, 0.0251), Vector3d(0.0289, 0.0110, 0.0372), Vector3d(-0.0291, 0.0103, 0.0372), Vector3d(-0.0282, -0.0600, 0.0251)}},
{"LeftLink5",
{Vector3d(0.0290, 0.0328, -0.0184), Vector3d(-0.0282, 0.0330, -0.0190), Vector3d(-0.0284, -0.1144, -0.0341), Vector3d(0.0288, -0.1145, -0.0335), Vector3d(0.0282, -0.1208, 0.0281), Vector3d(0.0284, 0.0265, 0.0432), Vector3d(-0.0288, 0.0266, 0.0427), Vector3d(-0.0290, -0.1207, 0.0275)}},
{"LeftLink6",
{Vector3d(0.0492, 0.0104, -0.0290), Vector3d(-0.0023, 0.0469, -0.0290), Vector3d(-0.0404, -0.0069, -0.0290), Vector3d(0.0111, -0.0434, -0.0290), Vector3d(0.0111, -0.0434, 0.0000), Vector3d(0.0492, 0.0104, 0.0000), Vector3d(-0.0023, 0.0469, 0.0000), Vector3d(-0.0404, -0.0069, 0.0000)}},
{"RightLink1",
{Vector3d(0.0411, 0.0456, -0.1191), Vector3d(-0.0409, 0.0458, -0.1191), Vector3d(-0.0411, -0.0444, -0.1013), Vector3d(0.0409, -0.0446, -0.1013), Vector3d(0.0410, -0.0137, 0.0545), Vector3d(0.0412, 0.0765, 0.0366), Vector3d(-0.0408, 0.0767, 0.0366), Vector3d(-0.0410, -0.0135, 0.0545)}},
{"RightLink2",
{Vector3d(0.3025, 0.0329, 0.0109), Vector3d(0.2879, 0.0332, -0.0733), Vector3d(0.2858, -0.0478, -0.0732), Vector3d(0.3004, -0.0481, 0.0110), Vector3d(-0.0349, -0.0396, 0.0692), Vector3d(-0.0329, 0.0414, 0.0691), Vector3d(-0.0475, 0.0417, -0.0150), Vector3d(-0.0496, -0.0393, -0.0149)}},
{"RightLink3",
{Vector3d(0.0464, 0.0342, 0.0241), Vector3d(-0.0012, 0.0428, -0.0180), Vector3d(-0.0025, -0.1243, -0.0505), Vector3d(0.0451, -0.1329, -0.0084), Vector3d(0.0019, -0.1416, 0.0386), Vector3d(0.0032, 0.0254, 0.0710), Vector3d(-0.0443, 0.0340, 0.0289), Vector3d(-0.0456, -0.1331, -0.0036)}},
{"RightLink4",
{Vector3d(0.0295, -0.0388, -0.0933), Vector3d(-0.0285, -0.0395, -0.0933), Vector3d(-0.0282, -0.0600, 0.0251), Vector3d(0.0298, -0.0592, 0.0251), Vector3d(0.0289, 0.0110, 0.0372), Vector3d(0.0286, 0.0314, -0.0811), Vector3d(-0.0294, 0.0307, -0.0811), Vector3d(-0.0291, 0.0103, 0.0372)}},
{"RightLink5",
{Vector3d(0.0288, -0.1145, -0.0335), Vector3d(-0.0284, -0.1144, -0.0341), Vector3d(-0.0290, -0.1207, 0.0275), Vector3d(0.0282, -0.1208, 0.0281), Vector3d(0.0284, 0.0265, 0.0432), Vector3d(0.0290, 0.0328, -0.0184), Vector3d(-0.0282, 0.0330, -0.0190), Vector3d(-0.0288, 0.0266, 0.0427)}},
{"RightLink6",
{Vector3d(0.0492, 0.0104, -0.0290), Vector3d(-0.0023, 0.0469, -0.0290), Vector3d(-0.0404, -0.0069, -0.0290), Vector3d(0.0111, -0.0434, -0.0290), Vector3d(0.0111, -0.0434, 0.0000), Vector3d(0.0492, 0.0104, 0.0000), Vector3d(-0.0023, 0.0469, 0.0000), Vector3d(-0.0404, -0.0069, 0.0000)}},
{"base_link",
{Vector3d(0.2085, 0.1895, -0.0856), Vector3d(-0.1905, 0.1895, -0.0880), Vector3d(-0.1905, -0.1895, -0.0880), Vector3d(0.2085, -0.1895, -0.0856), Vector3d(0.2071, -0.1895, 0.1679), Vector3d(0.2071, 0.1895, 0.1679), Vector3d(-0.1920, 0.1895, 0.1656), Vector3d(-0.1920, -0.1895, 0.1656)}},
{"base_link_leftarm",
{Vector3d(0.0661, -0.0353, 0.1385), Vector3d(0.0661, -0.0353, -0.0000), Vector3d(-0.0339, -0.0699, -0.0000), Vector3d(-0.0339, -0.0699, 0.1385), Vector3d(-0.0698, 0.0339, 0.1385), Vector3d(0.0302, 0.0685, 0.1385), Vector3d(0.0302, 0.0685, -0.0000), Vector3d(-0.0698, 0.0339, -0.0000)}},
{"base_link_rightarm",
{Vector3d(0.0661, -0.0353, -0.0000), Vector3d(0.0302, 0.0685, -0.0000), Vector3d(-0.0698, 0.0339, -0.0000), Vector3d(-0.0339, -0.0699, -0.0000), Vector3d(-0.0339, -0.0699, 0.1385), Vector3d(0.0661, -0.0353, 0.1385), Vector3d(0.0302, 0.0685, 0.1385), Vector3d(-0.0698, 0.0339, 0.1385)}},
{"body_2_link",
{Vector3d(0.1595, 0.0756, -0.0750), Vector3d(-0.1415, 0.0735, -0.0750), Vector3d(-0.1390, -0.2855, -0.0750), Vector3d(0.1620, -0.2834, -0.0750), Vector3d(0.1620, -0.2834, 0.5416), Vector3d(0.1595, 0.0756, 0.5416), Vector3d(-0.1415, 0.0735, 0.5416), Vector3d(-0.1390, -0.2855, 0.5416)}},
{"body_link",
{Vector3d(0.0593, 0.1034, -0.0010), Vector3d(-0.0842, 0.1024, -0.0010), Vector3d(-0.0828, -0.1036, -0.0010), Vector3d(0.0607, -0.1026, -0.0010), Vector3d(0.0607, -0.1026, 0.1600), Vector3d(0.0593, 0.1034, 0.1600), Vector3d(-0.0842, 0.1024, 0.1600), Vector3d(-0.0828, -0.1036, 0.1600)}},
{"head_link",
{Vector3d(0.0672, 0.1175, -0.0000), Vector3d(-0.0658, 0.1165, 0.0000), Vector3d(-0.0642, -0.1175, 0.0000), Vector3d(0.0689, -0.1165, -0.0000), Vector3d(0.0689, -0.1165, 0.2031), Vector3d(0.0672, 0.1175, 0.2031), Vector3d(-0.0658, 0.1165, 0.2031), Vector3d(-0.0642, -0.1175, 0.2031)}},
{"left_behind_hip_link",
{Vector3d(0.0626, 0.0721, 0.0288), Vector3d(-0.1058, 0.0721, -0.4340), Vector3d(-0.1058, 0.0000, -0.4340), Vector3d(0.0626, 0.0000, 0.0288), Vector3d(-0.0295, 0.0000, 0.0623), Vector3d(-0.0295, 0.0721, 0.0623), Vector3d(-0.1979, 0.0721, -0.4005), Vector3d(-0.1979, 0.0000, -0.4005)}},
{"left_behind_leg_link",
{Vector3d(0.0648, -0.0402, -0.0206), Vector3d(0.0648, 0.0235, -0.0206), Vector3d(-0.0927, 0.0235, -0.4532), Vector3d(-0.0927, -0.0402, -0.4532), Vector3d(-0.2204, -0.0402, -0.4068), Vector3d(-0.0629, -0.0402, 0.0259), Vector3d(-0.0629, 0.0235, 0.0259), Vector3d(-0.2204, 0.0235, -0.4068)}},
{"left_behind_wheel_link",
{Vector3d(0.0852, 0.0370, -0.0945), Vector3d(-0.0944, 0.0370, -0.0853), Vector3d(-0.0944, -0.0125, -0.0853), Vector3d(0.0852, -0.0125, -0.0945), Vector3d(0.0944, -0.0125, 0.0853), Vector3d(0.0944, 0.0370, 0.0853), Vector3d(-0.0852, 0.0370, 0.0945), Vector3d(-0.0852, -0.0125, 0.0945)}},
{"left_front_hip_link",
{Vector3d(0.1987, 0.1315, -0.3903), Vector3d(0.1020, 0.1315, -0.4259), Vector3d(0.1020, 0.0190, -0.4259), Vector3d(0.1987, 0.0190, -0.3903), Vector3d(0.0305, 0.0190, 0.0661), Vector3d(0.0305, 0.1315, 0.0661), Vector3d(-0.0661, 0.1315, 0.0305), Vector3d(-0.0661, 0.0190, 0.0305)}},
{"left_front_knee_link",
{Vector3d(0.2234, 0.0230, -0.3181), Vector3d(0.1136, 0.0230, -0.3665), Vector3d(0.1136, -0.0620, -0.3665), Vector3d(0.2234, -0.0620, -0.3181), Vector3d(0.0518, -0.0620, 0.0708), Vector3d(0.0518, 0.0230, 0.0708), Vector3d(-0.0580, 0.0230, 0.0224), Vector3d(-0.0580, -0.0620, 0.0224)}},
{"left_front_roll_link",
{Vector3d(0.0960, 0.0565, 0.0000), Vector3d(-0.0060, 0.0565, -0.1020), Vector3d(-0.0060, -0.0285, -0.1020), Vector3d(0.0960, -0.0285, 0.0000), Vector3d(-0.0060, -0.0285, 0.1020), Vector3d(-0.0060, 0.0565, 0.1020), Vector3d(-0.1080, 0.0565, -0.0000), Vector3d(-0.1080, -0.0285, -0.0000)}},
{"left_front_wheel_link",
{Vector3d(0.1223, 0.0000, -0.0336), Vector3d(-0.0336, 0.0000, -0.1223), Vector3d(-0.0336, -0.0570, -0.1223), Vector3d(0.1223, -0.0570, -0.0336), Vector3d(0.0336, -0.0570, 0.1223), Vector3d(0.0336, 0.0000, 0.1223), Vector3d(-0.1223, 0.0000, 0.0336), Vector3d(-0.1223, -0.0570, 0.0336)}},
{"right_behind_hip_link",
{Vector3d(-0.1058, -0.0000, -0.4340), Vector3d(-0.1979, -0.0000, -0.4005), Vector3d(-0.1979, -0.0721, -0.4005), Vector3d(-0.1058, -0.0721, -0.4340), Vector3d(0.0626, -0.0721, 0.0288), Vector3d(0.0626, -0.0000, 0.0288), Vector3d(-0.0295, -0.0000, 0.0623), Vector3d(-0.0295, -0.0721, 0.0623)}},
{"right_behind_leg_link",
{Vector3d(0.0648, 0.0402, -0.0206), Vector3d(-0.0927, 0.0402, -0.4532), Vector3d(-0.0927, -0.0235, -0.4532), Vector3d(0.0648, -0.0235, -0.0206), Vector3d(-0.0629, -0.0235, 0.0259), Vector3d(-0.0629, 0.0402, 0.0259), Vector3d(-0.2204, 0.0402, -0.4068), Vector3d(-0.2204, -0.0235, -0.4068)}},
{"right_behind_wheel_link",
{Vector3d(0.1259, 0.0125, -0.0183), Vector3d(-0.0182, 0.0125, -0.1259), Vector3d(-0.0182, -0.0370, -0.1259), Vector3d(0.1259, -0.0370, -0.0183), Vector3d(0.0182, -0.0370, 0.1259), Vector3d(0.0182, 0.0125, 0.1259), Vector3d(-0.1259, 0.0125, 0.0183), Vector3d(-0.1259, -0.0370, 0.0183)}},
{"right_front_hip_link",
{Vector3d(0.1956, -0.0190, -0.3918), Vector3d(0.0987, -0.0190, -0.4267), Vector3d(0.0987, -0.1320, -0.4267), Vector3d(0.1956, -0.1320, -0.3918), Vector3d(0.0310, -0.1320, 0.0659), Vector3d(0.0310, -0.0190, 0.0659), Vector3d(-0.0659, -0.0190, 0.0310), Vector3d(-0.0659, -0.1320, 0.0310)}},
{"right_front_knee_link",
{Vector3d(0.2234, 0.0620, -0.3181), Vector3d(0.1136, 0.0620, -0.3665), Vector3d(0.1136, -0.0230, -0.3665), Vector3d(0.2234, -0.0230, -0.3181), Vector3d(0.0518, -0.0230, 0.0708), Vector3d(0.0518, 0.0620, 0.0708), Vector3d(-0.0580, 0.0620, 0.0224), Vector3d(-0.0580, -0.0230, 0.0224)}},
{"right_front_roll_link",
{Vector3d(0.0960, 0.0285, 0.0000), Vector3d(-0.0060, 0.0285, -0.1020), Vector3d(-0.0060, -0.0565, -0.1020), Vector3d(0.0960, -0.0565, 0.0000), Vector3d(-0.0060, -0.0565, 0.1020), Vector3d(-0.0060, 0.0285, 0.1020), Vector3d(-0.1080, 0.0285, -0.0000), Vector3d(-0.1080, -0.0565, -0.0000)}},
{"right_front_wheel_link",
{Vector3d(0.1262, 0.0528, -0.0125), Vector3d(-0.0125, 0.0528, -0.1262), Vector3d(-0.0125, -0.0042, -0.1262), Vector3d(0.1262, -0.0042, -0.0125), Vector3d(0.0125, -0.0042, 0.1262), Vector3d(0.0125, 0.0528, 0.1262), Vector3d(-0.1262, 0.0528, 0.0125), Vector3d(-0.1262, -0.0042, 0.0125)}},
};
std::array<Vector3d, 8> eigen_points_arr = pointMap.at(col_struct.link_name);
std::vector<Eigen::Vector3d> eigen_points(eigen_points_arr.begin(), eigen_points_arr.end());
OBB obb = gjk_interface::createOBBFromPoints(eigen_points);
col_struct.obbModelList.push_back(obb);
return 0;
}
int RobotDescription::InitCollisionStructureList(const urdf::Model &urdf_model)
{
int result = 0;
int linkIndex = 0;
for (const auto& link_pair : urdf_model.links_) {
// link_pair是一个键值对: 键为链接名称,值为链接指针
urdf::LinkConstSharedPtr link = link_pair.second;
for (const auto& collision : link->collision_array) {
CollisionModel colStruct;
colStruct.link_name = link->name;
colStruct.geometry_type = collision->geometry->type;
linkCollisionMap_[link->name] = linkIndex;
int obbCnt = 1;
if (collision->geometry->type == urdf::Geometry::BOX) {
urdf::Box* box = dynamic_cast<urdf::Box*>(collision->geometry.get());
std::vector<Eigen::Vector3d> obb_points = {
Eigen::Vector3d(-box->dim.x / 2, -box->dim.y / 2, -box->dim.z / 2),
Eigen::Vector3d(box->dim.x / 2, -box->dim.y / 2, -box->dim.z / 2),
Eigen::Vector3d(-box->dim.x / 2, box->dim.y / 2, -box->dim.z / 2),
Eigen::Vector3d(box->dim.x / 2, box->dim.y / 2, -box->dim.z / 2),
Eigen::Vector3d(-box->dim.x / 2, -box->dim.y / 2, box->dim.z / 2),
Eigen::Vector3d(box->dim.x / 2, -box->dim.y / 2, box->dim.z / 2),
Eigen::Vector3d(-box->dim.x / 2, box->dim.y / 2, box->dim.z / 2),
Eigen::Vector3d(box->dim.x / 2, box->dim.y / 2, box->dim.z / 2)
};
OBB obb = gjk_interface::createOBBFromPoints(obb_points);
colStruct.obbModelList.push_back(obb);
} else if (collision->geometry->type == urdf::Geometry::MESH) {
urdf::Mesh* mesh = dynamic_cast<urdf::Mesh*>(collision->geometry.get());
colStruct.mesh_filename = mesh->filename;
result = GetMeshLinkdimensions(mesh->filename, colStruct);
if (result != 0) {
printf("Failed to get mesh dimensions for %s\n", mesh->filename.c_str());
return result;
}
}
for (int i = 0; i < obbCnt; i++) {
colStruct.obbLinkIndexList.push_back(maxObbCnt);
maxObbCnt++;
}
colStruct.link_index = linkIndex;
colStruct.joint_count = 0;
if (link->name == "base_link") {
rootLinkIndex_ = linkIndex;
colStruct.parent_link_index = -1;
colStruct.rotation = Quaterniond::Identity();
colStruct.offset = Vector3d::Zero();
printf("设置根链接: %s, 索引: %d 四元数: (%.4f, %.4f, %.4f, %.4f)\n", colStruct.link_name.c_str(), linkIndex,
colStruct.rotation.x(), colStruct.rotation.y(), colStruct.rotation.z(), colStruct.rotation.w());
}
collision_structures_.push_back(colStruct);
linkIndex++;
}
}
return result;
}
void RobotDescription::UpdatePolyhedrons()
{
int linkIndex = rootLinkIndex_;
CollisionModel *colStruct = &collision_structures_[linkIndex];
std::vector<JointsModel *> jointList;
int index = 0;
int maxJointCount = 0;
while (colStruct->joint_count > 0 || index < maxJointCount) {
for (int i = 0; i < colStruct->joint_count; i++) {
jointList.push_back(&colStruct->joint_list[i]);
maxJointCount++;
}
JointsModel *jointInfo = jointList[index];
Quaterniond rotation = collision_structures_[jointInfo->parent_link].rotation;
Vector3d offset = collision_structures_[jointInfo->parent_link].offset;
index++;
linkIndex = jointInfo->child_link;
colStruct = &collision_structures_[linkIndex];
offset = offset + rotation * jointInfo->nextLinkOffset;
colStruct->rotation = rotation;
colStruct->offset = offset;
for (size_t i = 0; i < colStruct->obbModelList.size(); i++) {
OBB obb = gjk_interface::updateOBBFromPoints(colStruct->obbModelList[i],
offset,
rotation);
printf("更新链接 %s 的 OBB:\n", colStruct->link_name.c_str());
printf("中心点: (%.4f, %.4f, %.4f)\n", obb.center(0), obb.center(1), obb.center(2));
/*printf("轴向:\n");
for (int j = 0; j < 3; j++) {
printf(" (%.4f, %.4f, %.4f)\n", obb.axis[j].x(), obb.axis[j].y(), obb.axis[j].z());
}
printf("半尺寸: (%.4f, %.4f, %.4f)\n", obb.halfExtent[0], obb.halfExtent[1], obb.halfExtent[2]);*/
}
}
}
int RobotDescription::InitLinkCollisionDetectMatrix(const std::string& srdf_str)
{
g_linkCollisionDetectMatrix = new bool[maxObbCnt * maxObbCnt];
for (int i = 0; i < maxObbCnt; ++i) {
for (int j = i + 1; j < maxObbCnt; ++j) {
g_linkCollisionDetectMatrix[i * maxObbCnt + j] = true;
}
}
tinyxml2::XMLDocument doc;
tinyxml2::XMLError error = doc.Parse(srdf_str.c_str());
if (error != tinyxml2::XML_SUCCESS) {
printf("Failed to parse SRDF: %s, length: %ld\n", doc.ErrorStr(), srdf_str.length());
return -1;
}
// 获取根节点<robot>
tinyxml2::XMLElement* robot_root = doc.FirstChildElement("robot");
if (!robot_root) {
printf("SRDF has no <robot> root node\n");
return -1;
}
int disable_count = 0;
for (tinyxml2::XMLElement* dc_elem = robot_root->FirstChildElement("disable_collisions");
dc_elem;
dc_elem = dc_elem->NextSiblingElement("disable_collisions")) {
std::string link1 = dc_elem->Attribute("link1");
std::string link2 = dc_elem->Attribute("link2");
int link1Index = linkCollisionMap_.find(link1) != linkCollisionMap_.end() ? linkCollisionMap_[link1] : -1;
int link2Index = linkCollisionMap_.find(link2) != linkCollisionMap_.end() ? linkCollisionMap_[link2] : -1;
if (link1Index != -1 && link2Index != -1) {
CollisionModel* colStruct1 = &collision_structures_[link1Index];
CollisionModel* colStruct2 = &collision_structures_[link2Index];
for (int obb1Idx : colStruct1->obbLinkIndexList) {
for (int obb2Idx : colStruct2->obbLinkIndexList) {
g_linkCollisionDetectMatrix[obb1Idx * maxObbCnt + obb2Idx] = false;
g_linkCollisionDetectMatrix[obb2Idx * maxObbCnt + obb1Idx] = false;
}
}
}
disable_count++;
}
printf("Initialized link collision detect matrix, disabled %d collision pairs. total %d\n", disable_count * 2, maxObbCnt * maxObbCnt);
for (int i = 0; i < maxObbCnt; ++i) {
for (int j = 0; j < maxObbCnt; ++j) {
if (g_linkCollisionDetectMatrix[i * maxObbCnt + j]) {
printf("true ");
} else {
printf("false ");
}
}
printf("\n");
}
return 0;
}
RobotDescription::RobotDescription(const std::string &urdf, const std::string &srdf)
{
urdf::Model urdf_model;
if (!urdf_model.initString(urdf)) {
printf("无法解析URDF模型\n");
return;
}
InitCollisionStructureList(urdf_model);
InitJoint(urdf_model);
UpdatePolyhedrons();
InitLinkCollisionDetectMatrix(srdf);
}
RobotDescription::~RobotDescription()
{
// 清理资源(如果有的话)
delete g_linkCollisionDetectMatrix;
}
/**
* @brief 以 std::string 形式读取文件全部内容
* @param file_path 文件绝对路径或相对路径
* @return 文件内容的 std::string
* @throws 若文件不存在、无法打开或读取失败,抛出 std::runtime_error
*/
std::string readFileToString(const std::string& file_path) {
// 1. 打开文件(二进制模式避免换行符转换,确保内容完整)
std::ifstream file(file_path, std::ios::in | std::ios::binary);
if (!file.is_open()) {
throw std::runtime_error("无法打开文件:" + file_path + "(可能路径错误或权限不足)\n");
}
// 2. 读取文件内容到 string
std::string content;
try {
// 定位到文件末尾,获取文件大小
file.seekg(0, std::ios::end);
// 预留内存(避免多次扩容,提升效率)
content.reserve(static_cast<size_t>(file.tellg()));
// 回到文件开头
file.seekg(0, std::ios::beg);
// 用迭代器读取全部内容(高效且简洁)
content.assign(std::istreambuf_iterator<char>(file), std::istreambuf_iterator<char>());
} catch (const std::exception& e) {
file.close(); // 异常时确保文件关闭
throw std::runtime_error("读取文件失败:" + file_path + "(错误信息:" + e.what() + "\n");
}
// 3. 关闭文件ifstream 析构时会自动关闭,但显式关闭更严谨)
file.close();
// 4. 可选:检查内容是否为空(根据需求决定是否抛出异常)
if (content.empty()) {
std::cerr << "[警告] 文件内容为空:" << file_path << std::endl;
// 若需要严格检查,可抛出异常:
// throw std::runtime_error("文件内容为空:" + file_path);
}
return content;
}
void searchRecursive(const fs::path& dir, const std::string& target, std::string& result, std::string& result_dir) {
for (const auto& entry : fs::directory_iterator(dir)) {
if (entry.is_directory()) {
searchRecursive(entry.path(), target, result, result_dir); // 递归子目录
if (!result.empty()) return; // 找到后提前返回
} else if (entry.is_regular_file() && entry.path().filename() == target) {
result = entry.path().string();
result_dir = entry.path().parent_path().string();
return;
}
}
}
std::string findFileInCurrentDir(const std::string& target_filename, std::string& result_dir) {
// 获取当前工作目录
std::string current_dir;
try {
current_dir = fs::current_path().string();
} catch (const fs::filesystem_error& e) {
throw std::runtime_error("无法获取当前目录:" + std::string(e.what()));
}
// 遍历当前目录下的所有文件(不递归子目录)
try {
std::string found_path;
searchRecursive(current_dir, target_filename, found_path, result_dir);
if (!found_path.empty()) {
return found_path; // 找到文件,返回路径
}
} catch (const fs::filesystem_error& e) {
throw std::runtime_error("遍历目录失败:" + std::string(e.what()));
}
// 未找到文件
return "";
}
int main(int argc, char *argv[])
{
UNUSED(argc);
UNUSED(argv);
// 示例URDF和SRDF字符串
std::string urdf_dir = "";
std::string srdf_dir = "";
std::string urdf_string = readFileToString(findFileInCurrentDir("FHrobot.urdf", urdf_dir));
std::string srdf_string = readFileToString(findFileInCurrentDir("FHrobot.srdf", srdf_dir));
printf("URDF路径: %s\n", urdf_dir.c_str());
printf("SRDF路径: %s\n", srdf_dir.c_str());
// 创建RobotDescription对象
RobotDescription robot_description(urdf_string, srdf_string);
// 其他逻辑...
return 0;
}