修改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;
}

View File

@@ -3,6 +3,7 @@
#include <vector>
#include <Eigen/Dense>
#include "gjk_interface.hpp"
typedef enum {
COLLISION_RESULT_NO_COLLISION = 0,
@@ -13,6 +14,7 @@ typedef enum {
struct OBB {
Eigen::Vector3d center; // 中心
Eigen::Vector3d axis[3]; // 3条正交的棱边方向轴单位向量
Eigen::Vector3d axisVectors[3]; // 3条正交的棱边方向轴非单位向量
double halfExtent[3]; // 沿各轴的半长(从中心到面的距离)
};
@@ -20,6 +22,8 @@ namespace gjk_interface {
bool gjkCollisionJudge(const std::vector<Eigen::Vector3d>& polyA, const std::vector<Eigen::Vector3d>& polyB);
OBB createOBBFromVertices(const std::vector<Eigen::Vector3d>& vertices,
const float length, const float width, const float height);
OBB createOBBFromPoints(const std::vector<Eigen::Vector3d>& vertices);
OBB updateOBBFromPoints(OBB originalOBB, Eigen::Vector3d translation, Eigen::Quaterniond rotation);
bool checkOBBCollision(const OBB &obb1, const OBB &obb2);
} // namespace gjk_interface

View File

@@ -186,6 +186,61 @@ namespace gjk_interface {
return obb;
}
OBB createOBBFromPoints(const std::vector<Eigen::Vector3d>& vertices) {
if (vertices.size() < 8) {
throw std::invalid_argument("OBB创建失败:必须输入至少8个顶点");
}
OBB obb;
for (int i = 1; i < 8; ++i) {
Vector3d vec1 = vertices[i] - vertices[0];
for (int j = i + 1; j < 7; ++j) {
Vector3d vec2 = vertices[j] - vertices[0];
if (vec1.dot(vec2) < 1e-4) {
for (int k = j + 1; k < 8; ++k) {
Vector3d vec3 = vertices[k] - vertices[0];
if (fabs(vec1.dot(vec3)) < 1e-4 && fabs(vec2.dot(vec3)) < 1e-4) {
// 找到3条互相正交的边
obb.axis[0] = vec1.normalized();
obb.axis[1] = vec2.normalized();
obb.axis[2] = vec3.normalized();
obb.axisVectors[0] = vec1;
obb.axisVectors[1] = vec2;
obb.axisVectors[2] = vec3;
// 计算中心点
obb.center = (vertices[i] + vertices[j] + vertices[k] - vertices[0]) * (1.0 / 2.0);
// 计算半长
obb.halfExtent[0] = vec1.norm() * (1.0 / 2.0);
obb.halfExtent[1] = vec2.norm() * (1.0 / 2.0);
obb.halfExtent[2] = vec3.norm() * (1.0 / 2.0);
return obb;
}
}
}
}
}
return obb;
}
OBB updateOBBFromPoints(OBB originalOBB, Eigen::Vector3d translation, Eigen::Quaterniond rotation) {
OBB updatedOBB;
// 更新中心点
updatedOBB.center = rotation * originalOBB.center + translation;
// 更新轴方向
for (int i = 0; i < 3; ++i) {
updatedOBB.axis[i] = rotation * originalOBB.axis[i];
updatedOBB.axisVectors[i] = rotation * originalOBB.axisVectors[i];
updatedOBB.halfExtent[i] = originalOBB.halfExtent[i];
}
return updatedOBB;
}
// 计算OBB在指定轴上的投影范围min, max
std::pair<double, double> projectOBB(const OBB& obb, const Vector3d& axis) {
// OBB中心在轴上的投影

View File

@@ -10,6 +10,10 @@ if(CMAKE_C_COMPILER_ID STREQUAL "GNU" OR CMAKE_C_COMPILER_ID STREQUAL "Clang")
endif()
add_compile_options(-g)
#set(CMAKE_BUILD_TYPE Release)
set(CGAL_DO_NOT_WARN_ABOUT_CMAKE_BUILD_TYPE TRUE)
set(CGAL_DATA_DIR ".")
# 全局设置 C++ 编译选项
# set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3")
# 全局设置 C 编译选项
@@ -50,6 +54,7 @@ find_package(trajectory_msgs REQUIRED)
find_package(control_msgs REQUIRED)
find_package(gjk_interface REQUIRED)
find_package(interfaces REQUIRED)
find_package(CGAL REQUIRED)
find_package(moveit_core REQUIRED)
find_package(moveit_ros_planning_interface REQUIRED)
@@ -66,6 +71,7 @@ set(SOURCES
simulator/rm_arm_simulator.cpp
simulator/trapezoidal_trajectory_kinematics.cpp
simulator/rm_driver_kinematics.cpp
simulator/col_simulator.cpp
src/goal_manager.cpp
driver/arm_driver.cpp
driver/rm_arm_driver.cpp
@@ -94,6 +100,7 @@ find_library(RMAN_API_LIB NAMES api_cpp PATHS "${CMAKE_CURRENT_SOURCE_DIR}/Robot
# 链接库
target_link_libraries(rm_arm_control ${RMAN_API_LIB})
target_link_libraries(rm_arm_control CGAL::CGAL)
# 如果是 UNIX 平台且不是 ARM 平台,确保动态库文件可以在运行时被找到(这一步通常不是必须的,但在某些配置下可能需要)
if(UNIX)

View File

@@ -5,6 +5,7 @@
#include <map>
#include <urdf_model/pose.h>
#include <std_msgs/msg/string.hpp>
#include <moveit/collision_detection_bullet/collision_detector_allocator_bullet.h>
#include "arm_define.h"
#include "arm_driver_define.hpp"
#include "gjk_interface.hpp"
@@ -18,25 +19,23 @@ typedef enum {
BODY_CNT
} BodyListE;
typedef enum {
/*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;
} FrameChangeTypeE;*/
typedef std::vector<Eigen::Vector3d> Polyhedron;
struct JointInfo {
struct JointsInfo {
std::string name; // 关节名称
int type; // 关节类型
int parent_link; // 父连杆
int child_link; // 子连杆
Eigen::Quaterniond rotationAll;
Eigen::Vector3d axis; // 关节轴
Eigen::Vector3d offset; // 关节偏移
Eigen::Vector3d leftBottom; // 左下角点关于关节原点偏移
Eigen::Vector3d nextLinkOffset; // 下一个连杆关于关节原点偏移
Eigen::Quaterniond rotation; // 关节旋转
double limit_lower;
@@ -46,14 +45,17 @@ struct JointInfo {
float *angle[COLLISION_CHECK_SIMPLE_CNT]; // 关节角度
};
struct CollisionStructure {
struct CollisionStructureInfo {
std::string link_name; // 所属链接名称
std::string geometry_type; // 几何类型
std::string mesh_filename; // mesh文件路径如STL
std::vector<double> mesh_bounds; // 网格边界盒 [min_x, max_x, min_y, max_y, min_z, max_z]
Eigen::Quaterniond rotationAdd; // 不平行轴关节叠加旋转
std::vector<OBB> obbModelList; // 网格边界盒 [min_x, max_x, min_y, max_y, min_z, max_z]
std::vector<int> obbLinkIndexList; // 网格边界盒所属链接索引
Eigen::Quaterniond rotation[COLLISION_CHECK_SIMPLE_CNT]; // 链接旋转
Eigen::Vector3d offset[COLLISION_CHECK_SIMPLE_CNT]; // 链接偏移
bool rotation_add_flag;
std::vector<JointInfo> joint_list;
std::vector<JointsInfo> joint_list;
int joint_count;
int link_index;
int parent_link_index;
@@ -62,8 +64,7 @@ struct CollisionStructure {
class CollisionSimulator
{
public:
CollisionSimulator(std_msgs::msg::String::SharedPtr urdf_string_ptr, float **jointsList, KinematicsManager **trajectory);
CollisionSimulator(std::string urdf_string, float **jointsList, KinematicsManager **trajectory);
CollisionSimulator(std::string urdf_string, std::string srdf_string, float **jointsList, KinematicsManager **trajectory);
~CollisionSimulator();
int CheckCollision();
@@ -73,26 +74,27 @@ public:
private:
void InitCollisionSimulator(const urdf::Model &urdf_model, float **jointsList, KinematicsManager **trajectory);
int CheckJointsAngleLimit(float *joints, int bodyType);
int CheckJointsAngleLimit(int simple, int bodyType);
int InitPolyhedrons(const urdf::Model &urdf_model);
void InitArmSinglePolyhedron(int index, Polyhedron *poly, Vector3d &origin, const Vector3d &offset, const Matrix3d &rotation);
void UpdatePolyhedrons(int startLinkIndex, int endLinkIndex, int simple, float *jointList);
int CheckCollisionInner(std::vector<OBB> *addedOBBs, std::vector<OBB> *addedOBBsNext_);
void UpdatePolyhedrons(int bodyType, int simple);
int InitCollisionStructureList(const urdf::Model &urdf_model);
int GetMeshLinkdimensions(const std::string& filename, CollisionStructure& col_struct);
std::pair<Eigen::Vector3d, Eigen::Matrix3d> GetBodyTransform(int startIndex);
int GetMeshLinkdimensions(const std::string& filename, CollisionStructureInfo& col_struct);
int InitJoint(const urdf::Model &urdf_model);
int InitJointModel();
void InitPolyhedronsList();
void UpdateArmPolyhedrons();
int InitLinkCollisionDetectMatrix(const std::string& srdf_str);
KinematicsManager *trajectory_[BODY_CNT];
std::vector<Polyhedron> polyhedrons_[COLLISION_CHECK_SIMPLE_CNT];
std::vector<OBB> addedOBBs_[COLLISION_CHECK_SIMPLE_CNT];
std::vector<CollisionStructure> collision_structures_;
std::vector<JointInfo> jointMap_;
std::vector<CollisionStructureInfo> collision_structures_;
std::vector<JointsInfo> jointMap_;
int simpleUpdateIndex_;
int rootLinkIndex_;
int maxObbCnt;
float *joints_[COLLISION_CHECK_SIMPLE_CNT][BODY_CNT];
std::unordered_map<int, Polyhedron> addedPolyhedrons_;

View File

@@ -6,6 +6,75 @@ from launch_ros.substitutions import FindPackageShare
from launch.actions import OpaqueFunction
import os
def open_file(file_name, context):
try:
package_share = FindPackageShare(package='rm_arm_control').perform(context)
# 1. 计算SRDF文件路径并解析
file_path = PathJoinSubstitution(
[package_share, 'urdf', file_name] # 替换为实际的SRDF路径
).perform(context) # context 是LaunchContext对象通常在generate_launch_description中可用
# 2. 检查路径是否存在
if not os.path.exists(file_path):
raise FileNotFoundError(f"SRDF文件不存在: {file_path}")
# 3. 检查路径是否为文件(避免目录路径)
if not os.path.isfile(file_path):
raise IsADirectoryError(f"指定路径是目录,不是文件: {file_path}")
# 4. 尝试打开并读取文件
with open(file_path, 'r') as f:
file_content = f.read()
# 5. 检查文件内容是否为空
if not file_content.strip(): # 忽略纯空白内容
raise ValueError(f"文件内容为空: {file_path}")
# 6. 可选简单验证XML格式是否合法检查根节点
if '<robot' not in file_content:
raise SyntaxError(f"文件格式无效,未找到<robot>根节点: {file_path}")
# 读取成功后的逻辑(如加载到参数服务器)
print(f"成功读取SRDF文件: {file_path}")
return file_content # 返回读取的内容,或根据需要处理
except FileNotFoundError as e:
# 文件不存在错误
print(f"错误: {str(e)}")
print("请检查路径是否正确确保SRDF文件存在于指定目录")
# 可根据需要抛出异常终止launch或使用return None等方式处理
raise # 抛出异常终止launch启动
except IsADirectoryError as e:
# 路径是目录而非文件
print(f"错误: {str(e)}")
print("请检查路径是否指向具体的SRDF文件而非目录")
raise
except PermissionError:
# 无权限读取文件
print(f"错误: 没有权限读取SRDF文件: {file_path}")
print("请检查文件权限,确保当前用户有读取权限")
raise
except ValueError as e:
# 文件内容为空
print(f"错误: {str(e)}")
print("请检查SRDF文件是否被正确生成内容不能为空")
raise
except SyntaxError as e:
# XML格式初步验证失败
print(f"错误: {str(e)}")
print("请检查SRDF文件是否为有效的XML格式")
raise
except Exception as e:
# 捕获其他未预料的错误
print(f"读取SRDF文件时发生未知错误: {str(e)}")
raise
def load_urdf(context, *args, **kwargs):
nodeList = []
@@ -21,6 +90,8 @@ def load_urdf(context, *args, **kwargs):
with open(urdf_path, 'r') as f:
urdf_content = f.read()
srdf_content = open_file('FHrobot.srdf', context)
robot_controller = Node(
package='rm_arm_control',
executable='rm_arm_control',
@@ -28,6 +99,7 @@ def load_urdf(context, *args, **kwargs):
output='screen',
parameters=[{
'robot_description': urdf_content,
'robot_description_semantic': srdf_content,
'use_sim_time': False
}]
)

View File

@@ -4,8 +4,14 @@
#include <string>
#include <rclcpp/rclcpp.hpp>
#include <moveit/robot_model/robot_model.h>
#include <CGAL/optimal_bounding_box.h>
#include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
#include <CGAL/Surface_mesh.h>
#include "col_simulator.hpp"
typedef CGAL::Exact_predicates_inexact_constructions_kernel CgalK;
typedef CgalK::Point_3 CgalPoint;
using namespace Eigen;
const int g_bodyLinkCnt[BODY_CNT] = {USED_ARM_DOF + 1, USED_ARM_DOF + 1, USED_OTHER_DOF + 1};
const int g_jointLinkCnt[BODY_CNT] = {USED_ARM_DOF, USED_ARM_DOF, USED_OTHER_DOF};
@@ -13,120 +19,157 @@ float g_leftArmJoints[COLLISION_CHECK_SIMPLE_CNT][USED_ARM_DOF] = {0};
float g_rightArmJoints[COLLISION_CHECK_SIMPLE_CNT][USED_ARM_DOF] = {0};
float g_otherJoints[COLLISION_CHECK_SIMPLE_CNT][USED_OTHER_DOF] = {0};
const std::string g_bodyStartName[BODY_CNT] = {"LeftLink1", "RightLink1", "base_link"};
bool *g_linkCollisionDetectMatrix = nullptr;
int g_linkStartIndex[BODY_CNT] = {0};
#define POLYHEDRONS_POINTS_CNT (8)
enum OriginBoxIndex {
LEFT_ARM_ORIGIN = 0,
LEFT_ARM_UPDATE_ORIGIN,
RIGHT_ARM_ORIGIN = g_bodyLinkCnt[BODY_TYPE_LEFT_ARM],
RIGHT_ARM_UPDATE_ORIGIN,
OTHER_ORIGIN = g_bodyLinkCnt[BODY_TYPE_LEFT_ARM] + g_bodyLinkCnt[BODY_TYPE_RIGHT_ARM],
BASE = g_bodyLinkCnt[BODY_TYPE_LEFT_ARM] + g_bodyLinkCnt[BODY_TYPE_RIGHT_ARM] + g_bodyLinkCnt[BODY_TYPE_OTHERS],
};
const int g_linkStartIndex[BODY_CNT + 1] = {
LEFT_ARM_UPDATE_ORIGIN,
RIGHT_ARM_UPDATE_ORIGIN,
OTHER_ORIGIN,
BASE
};
#define ROOT (BASE - 1)
bool g_linkCollisionDetecMatrix[OTHER_ORIGIN][BASE] = {false};
Vector3d g_origin[BASE] = {Vector3d::Zero()};
Vector3d g_offset[BASE] = {Vector3d::Zero()};
Vector3d g_dir[BASE] = {Vector3d::Zero()};
static double toRadians(float degrees) {
return (static_cast<double>(degrees)) * (M_PI / 180.0);
}
static int UpdateJointInfo(int i, int parent, Quaterniond &rotation, std::vector<JointInfo> &jointMap)
int CollisionSimulator::InitJointModel()
{
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;
int linkIndex = rootLinkIndex_;
CollisionStructureInfo *colStruct = &collision_structures_[linkIndex];
std::vector<JointsInfo *> 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++;
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;
}
JointsInfo *jointInfo = jointList[index];
rotationAll = jointInfo->rotation;
index++;
linkIndex = jointInfo->child_link;
colStruct = &collision_structures_[linkIndex];
for (int i = 0; i < colStruct->obbModelList.size(); i++) {
colStruct->obbModelList[i] = gjk_interface::updateOBBFromPoints(colStruct->obbModelList[i],
Vector3d::Zero(),
rotationAll);
}
}
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(const urdf::Model &urdf_model, std::vector<JointInfo> &jointMap)
int CollisionSimulator::InitJoint(const urdf::Model &urdf_model)
{
const std::map<std::string, int> jointNameToIndexMap = {
{"left_joint1", 0}, {"left_joint2", 1}, {"left_joint3", 2}, {"left_joint4", 3}, {"left_joint5", 4}, {"left_joint6", 5},
{"right_joint1", 0}, {"right_joint2", 1}, {"right_joint3", 2}, {"right_joint4", 3}, {"right_joint5", 4}, {"right_joint6", 5},
{"left_behind_hip_joint", 0}, {"left_behind_leg_joint", 1}, {"left_behind_wheel_joint", 2}, {"right_behind_hip_joint", 3},
{"right_behind_leg_joint", 4}, {"right_behind_wheel_joint", 5}, {"body_joint", 6}, {"body_2_joint", 7}, {"head_joint", 8},
{"left_front_roll_joint", 9}, {"left_front_hip_joint", 10}, {"left_front_knee_joint", 11},
{"left_front_wheel_joint", 12}, {"right_front_roll_joint", 13}, {"right_front_hip_joint", 14}, {"right_front_knee_joint", 15}, {"right_front_wheel_joint", 16}
};
const std::map<std::string, int> jointNameToBodyType = {
{"left_joint1", BODY_TYPE_LEFT_ARM}, {"left_joint2", BODY_TYPE_LEFT_ARM}, {"left_joint3", BODY_TYPE_LEFT_ARM}, {"left_joint4", BODY_TYPE_LEFT_ARM},
{"left_joint5", BODY_TYPE_LEFT_ARM}, {"left_joint6", BODY_TYPE_LEFT_ARM},
{"right_joint1", BODY_TYPE_RIGHT_ARM}, {"right_joint2", BODY_TYPE_RIGHT_ARM}, {"right_joint3", BODY_TYPE_RIGHT_ARM}, {"right_joint4", BODY_TYPE_RIGHT_ARM},
{"right_joint5", BODY_TYPE_RIGHT_ARM}, {"right_joint6", BODY_TYPE_RIGHT_ARM},
{"left_behind_hip_joint", BODY_TYPE_OTHERS}, {"left_behind_leg_joint", BODY_TYPE_OTHERS}, {"left_behind_wheel_joint", BODY_TYPE_OTHERS},
{"right_behind_hip_joint", BODY_TYPE_OTHERS}, {"right_behind_leg_joint", BODY_TYPE_OTHERS}, {"right_behind_wheel_joint", BODY_TYPE_OTHERS},
{"body_joint", BODY_TYPE_OTHERS}, {"body_2_joint", BODY_TYPE_OTHERS}, {"head_joint", BODY_TYPE_OTHERS}, {"left_front_roll_joint", BODY_TYPE_OTHERS},
{"left_front_hip_joint", BODY_TYPE_OTHERS}, {"left_front_knee_joint", BODY_TYPE_OTHERS}, {"left_front_wheel_joint", BODY_TYPE_OTHERS},
{"right_front_roll_joint", BODY_TYPE_OTHERS}, {"right_front_hip_joint", BODY_TYPE_OTHERS}, {"right_front_knee_joint", BODY_TYPE_OTHERS},
{"right_front_wheel_joint", BODY_TYPE_OTHERS}
};
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;
JointsInfo 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 {
RCLCPP_WARN(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Joint %s 的父链接 %s 未找到!", joint->name.c_str(), joint->parent_link_name.c_str());
return -1;
}
}
link = g_linkMap.find(joint->child_link_name);
if (link != g_linkMap.end()) {
jointInfo.child_link = link->second;
} else {
continue;
if (joint->child_link_name != "") {
if (linkCollisionMap_.find(joint->child_link_name) != linkCollisionMap_.end()) {
joint_info.child_link = linkCollisionMap_[joint->child_link_name];
} else {
RCLCPP_WARN(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Joint %s 的子链接 %s 未找到!", joint->name.c_str(), joint->child_link_name.c_str());
return -1;
}
}
jointInfo.offset = Vector3d(joint->parent_to_joint_origin_transform.position.x,
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);
jointInfo.rotation = Quaterniond(
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->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;
if (joint->type != urdf::Joint::FIXED) {
int jointAngleIndex = jointNameToIndexMap.at(joint->name);
int bodyType = jointNameToBodyType.at(joint->name);
for (int i = 0; i < COLLISION_CHECK_SIMPLE_CNT; i++) {
joint_info.angle[i] = &joints_[i][bodyType][jointAngleIndex];
}
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;
}
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;
jointMap_.push_back(joint_info);
CollisionStructureInfo *parentColStruct = &collision_structures_[joint_info.parent_link];
parentColStruct->joint_list.push_back(joint_info);
parentColStruct->joint_count++;
CollisionStructureInfo *childColStruct = &collision_structures_[joint_info.child_link];
childColStruct->parent_link_index = joint_info.parent_link;
}
InitJointModel();
return 0;
}
int CollisionSimulator::GetMeshLinkdimensions(const std::string& filename, CollisionStructure& col_struct)
int CollisionSimulator::GetMeshLinkdimensions(const std::string& filename, CollisionStructureInfo& col_struct)
{
// 这里可以添加读取网格文件并计算边界盒的代码
// 假设已经计算出边界盒的最小和最大坐标
col_struct.mesh_bounds = {min_x, max_x, min_y, max_y, min_z, max_z};
shapes::Mesh* mesh = shapes::createMeshFromResource(filename);
if (!mesh) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "无法加载网格文件: %s", 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));
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "计算%s得到的 OBB 顶点:", col_struct.link_name.c_str());
for (const auto& pt : obb_points) {
eigen_points.push_back(Eigen::Vector3d(pt.x(), pt.y(), pt.z()));
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "(%.4f, %.4f, %.4f)", pt.x(), pt.y(), pt.z());
}
OBB obb = gjk_interface::createOBBFromPoints(eigen_points);
col_struct.obbModelList.push_back(obb);
return 0;
}
@@ -138,14 +181,25 @@ int CollisionSimulator::InitCollisionStructureList(const urdf::Model &urdf_model
// link_pair是一个键值对: 键为链接名称,值为链接指针
urdf::LinkConstSharedPtr link = link_pair.second;
for (const auto& collision : link->collision_array) {
CollisionStructure colStruct;
CollisionStructureInfo 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());
colStruct.mesh_bounds = {-box->dim.x / 2, box->dim.x / 2,
-box->dim.y / 2, box->dim.y / 2,
-box->dim.z / 2, box->dim.z / 2};
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;
@@ -156,20 +210,87 @@ int CollisionSimulator::InitCollisionStructureList(const urdf::Model &urdf_model
}
}
colStruct.link_index = linkIndex;
linkIndex++;
for (int i = 0; i < obbCnt; i++) {
colStruct.obbLinkIndexList.push_back(maxObbCnt);
for (int j = 0; j < COLLISION_CHECK_SIMPLE_CNT; j++) {
addedOBBs_[j].push_back(colStruct.obbModelList[i]);
}
maxObbCnt++;
}
colStruct.joint_count = 0;
for (int i = 0; i < BODY_CNT; i++) {
if (link->name == g_bodyStartName[i]) {
g_linkStartIndex[i] = linkIndex;
if (i == BODY_TYPE_OTHERS) {
rootLinkIndex_ = linkIndex;
colStruct.parent_link_index = -1;
for (int j = 0; j < COLLISION_CHECK_SIMPLE_CNT; j++) {
colStruct.rotation[j] = Quaterniond::Identity();
colStruct.offset[j] = Vector3d::Zero();
}
}
break;
}
}
collision_structures_.push_back(colStruct);
linkIndex++;
}
}
return result;
}
int CollisionSimulator::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) {
RCLCPP_ERROR(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Failed to parse SRDF: %s, length: %ld", doc.ErrorStr(), srdf_str.length());
return -1;
}
// 获取根节点<robot>
tinyxml2::XMLElement* robot_root = doc.FirstChildElement("robot");
if (!robot_root) {
RCLCPP_ERROR(rclcpp::get_logger(GET_FUNC_LINE_STR()), "SRDF has no <robot> root node");
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) {
CollisionStructureInfo* colStruct1 = &collision_structures_[link1Index];
CollisionStructureInfo* 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++;
}
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Initialized link collision detect matrix, disabled %d collision pairs.", disable_count);
return 0;
}
int CollisionSimulator::InitPolyhedrons(const urdf::Model &urdf_model)
{
InitCollisionStructureList(urdf_model);
std::vector<CollisionStructure> collision_structures_temp;
InitJoint(urdf_model, jointMap_);
InitCollisionStructure(urdf_model, collision_structures_temp);
return RemakeCollisionStructureList(collision_structures_temp);
InitJoint(urdf_model);
return 0;
}
void CollisionSimulator::InitCollisionSimulator(const urdf::Model &urdf_model, float **jointsList, KinematicsManager **trajectory)
@@ -178,19 +299,21 @@ void CollisionSimulator::InitCollisionSimulator(const urdf::Model &urdf_model, f
joints_[i][BODY_TYPE_LEFT_ARM] = g_leftArmJoints[i];
joints_[i][BODY_TYPE_RIGHT_ARM] = g_rightArmJoints[i];
joints_[i][BODY_TYPE_OTHERS] = g_otherJoints[i];
for (int j = 0; j < BODY_CNT; j++) {
for (int j = 0; j < BODY_TYPE_OTHERS; j++) {
for (int k = 0; k < g_jointLinkCnt[j]; k++) {
joints_[i][j][k] = jointsList[j][k];
}
}
for (int j = 0; j < g_jointLinkCnt[BODY_TYPE_OTHERS]; j++) {
joints_[i][BODY_TYPE_OTHERS][j] = 0;
}
}
InitPolyhedrons(urdf_model);
InitPolyhedronsList();
UpdateArmPolyhedrons();
}
CollisionSimulator::CollisionSimulator(std::string urdf_string, float **jointsList, KinematicsManager **trajectory)
CollisionSimulator::CollisionSimulator(std::string urdf_string, std::string srdf_string, float **jointsList, KinematicsManager **trajectory)
{
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "CollisionSimulator: 初始化机械臂碰撞检测模块...");
urdf::Model urdf_model;
@@ -200,55 +323,23 @@ CollisionSimulator::CollisionSimulator(std::string urdf_string, float **jointsLi
return;
}
InitCollisionSimulator(urdf_model, jointsList, trajectory);
InitLinkCollisionDetectMatrix(srdf_string);
}
CollisionSimulator::CollisionSimulator(std_msgs::msg::String::SharedPtr urdf_string_ptr, float **jointsList, KinematicsManager **trajectory)
CollisionSimulator::~CollisionSimulator()
{
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "CollisionSimulator: 初始化机械臂碰撞检测模块...");
std::string urdf_string = urdf_string_ptr->data;
// 解析URDF模型
urdf::Model urdf_model;
simpleUpdateIndex_ = 0;
if (!urdf_model.initString(urdf_string)) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "无法解析URDF模型");
return;
}
InitCollisionSimulator(urdf_model, jointsList, trajectory);
}
void CollisionSimulator::InitArmSinglePolyhedron(int index, Polyhedron *poly,
Vector3d &origin, const Vector3d &offset, const Matrix3d &rotation)
{
float length = collision_structures_[index].dimensions[0]; // 长度沿u方向
float width = collision_structures_[index].dimensions[1]; // 宽度沿v方向
float height = 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];
if (g_linkCollisionDetectMatrix != nullptr) {
delete[] g_linkCollisionDetectMatrix;
g_linkCollisionDetectMatrix = nullptr;
}
}
static int CheckCollisionInner(std::vector<OBB> *addedOBBs, std::vector<OBB> *addedOBBsNext_)
int CollisionSimulator::CheckCollisionInner(std::vector<OBB> *addedOBBs, std::vector<OBB> *addedOBBsNext_)
{
for (int i = g_linkStartIndex[LEFT_ARM_ORIGIN]; i < g_linkStartIndex[OTHER_ORIGIN]; ++i) {
for (int j = i + 1; j < BASE; ++j) {
if (!g_linkCollisionDetecMatrix[i][j]) {
int result = OK;
for (int i = 0; i < maxObbCnt; ++i) {
for (int j = i + 1; j < maxObbCnt; ++j) {
if (!g_linkCollisionDetectMatrix[i * maxObbCnt + j]) {
continue;
}
bool inCollision = gjk_interface::checkOBBCollision((*addedOBBsNext_)[i], (*addedOBBsNext_)[j]);
@@ -263,185 +354,83 @@ static int CheckCollisionInner(std::vector<OBB> *addedOBBs, std::vector<OBB> *ad
}
}
}
return OK;
return result;
}
std::pair<Vector3d, Matrix3d> CollisionSimulator::GetBodyTransform(int startIndex)
void CollisionSimulator::UpdatePolyhedrons(int bodyType, int simple)
{
Vector3d offset_vec;
Matrix3d rotation = Matrix3d::Identity();
std::stack <int> indexStack;
int bodyIndex = startIndex;
while (bodyIndex != ROOT) {
indexStack.push(bodyIndex);
bodyIndex = jointMap_[bodyIndex].parent_link;
}
while (!indexStack.empty()) {
int currentIndex = indexStack.top();
indexStack.pop();
if (jointMap_[currentIndex].type == urdf::Joint::FIXED) {
offset_vec = offset_vec + rotation * g_origin[currentIndex];
} else if (jointMap_[currentIndex].type == urdf::Joint::REVOLUTE) {
double angleRad = toRadians(jointMap_[currentIndex].angle);
rotation = AngleAxisd(angleRad, rotation * g_dir[currentIndex]) * rotation;
offset_vec = offset_vec + rotation * g_origin[currentIndex];
} else if (jointMap_[currentIndex].type == urdf::Joint::PRISMATIC) {
double displacement = jointMap_[currentIndex].angle;
offset_vec = offset_vec + rotation * (g_origin[currentIndex] + g_dir[currentIndex] * displacement);
int linkIndex = g_linkStartIndex[bodyType];
CollisionStructureInfo *colStruct = &collision_structures_[linkIndex];
std::vector<JointsInfo *> 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++;
}
}
return { offset_vec, rotation };
}
JointsInfo *jointInfo = jointList[index];
Quaterniond rotation = colStruct->rotation[simple];
Vector3d offset = colStruct->offset[simple];
index++;
linkIndex = jointInfo->child_link;
colStruct = &collision_structures_[linkIndex];
void CollisionSimulator::UpdatePolyhedrons(int startLinkIndex, int endLinkIndex, int simple, float *jointList)
{
std::vector<Polyhedron> *armPolyhedrons = &(polyhedrons_[simple]);
auto [offset_vec, rotation] = GetBodyTransform(startLinkIndex);
for (int i = startLinkIndex + 1; i < endLinkIndex; i++) {
double angleRad = toRadians(jointList[i - startLinkIndex - 1]);
rotation = AngleAxisd(angleRad, rotation * g_dir[i]) * rotation;
InitArmSinglePolyhedron(i, &(*armPolyhedrons)[i],
offset_vec,
g_offset[i],
rotation);
addedOBBs_[simple][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[i],
collision_structures_[i].dimensions[0],
collision_structures_[i].dimensions[1],
collision_structures_[i].dimensions[2]);
if (jointInfo->type == urdf::Joint::REVOLUTE) {
double angleRad = toRadians(jointInfo->angle[simple][0]);
rotation = AngleAxisd(angleRad, rotation * jointInfo->axis) * rotation;
} else if (jointInfo->type == urdf::Joint::PRISMATIC) {
double displacement = jointInfo->angle[simple][0];
offset = offset + rotation * jointInfo->axis * displacement;
}
offset = offset + rotation * jointInfo->nextLinkOffset;
colStruct->rotation[simple] = rotation;
colStruct->offset[simple] = offset;
for (int i = 0; i < colStruct->obbModelList.size(); i++) {
int obbIndex = colStruct->obbLinkIndexList[i];
addedOBBs_[simple][obbIndex] = gjk_interface::updateOBBFromPoints(colStruct->obbModelList[i],
offset,
rotation);
}
}
}
void CollisionSimulator::InitPolyhedronsList()
{
for (int i = 0; i < COLLISION_CHECK_SIMPLE_CNT; i++) {
polyhedrons_[i].resize(BASE);
addedOBBs_[i].resize(BASE);
polyhedrons_[i][BASE].clear();
UpdatePolyhedrons(BODY_TYPE_OTHERS, i);
}
/*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 < COLLISION_CHECK_SIMPLE_CNT; simple++) {
for (int i = 0; i < BASE; i++) {
for (int j = 0; j < POLYHEDRONS_POINTS_CNT; j++) {
polyhedrons_[simple][i].push_back(Vector3d(0, 0, 0));
}
}
}
for (int simple = 0; simple < COLLISION_CHECK_SIMPLE_CNT; simple++) {
std::vector<Polyhedron> *armPolyhedrons = &(polyhedrons_[simple]);
Vector3d offset_temp = {0, 0 ,0};
Vector3d origin_point_offset = {0, 0 ,0};
if (collision_structures_[ROOT].geometry_type == "box") {
origin_point_offset = Vector3d(-collision_structures_[ROOT].dimensions[0] / 2,
-collision_structures_[ROOT].dimensions[1] / 2,
-collision_structures_[ROOT].dimensions[2] / 2);
} else if (collision_structures_[ROOT].geometry_type == "mesh") {
origin_point_offset = Vector3d(collision_structures_[ROOT].mesh_bounds[0],
collision_structures_[ROOT].mesh_bounds[2],
collision_structures_[ROOT].mesh_bounds[4]);
}
Matrix3d rotation = Matrix3d::Identity();
InitArmSinglePolyhedron(ROOT, &(*armPolyhedrons)[ROOT],
offset_temp,
origin_point_offset,
rotation);
addedOBBs_[simple][ROOT] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[ROOT],
collision_structures_[ROOT].dimensions[0],
collision_structures_[ROOT].dimensions[1],
collision_structures_[ROOT].dimensions[2]);
Vector3d offset_vec = g_origin[LEFT];
for (int i = LEFT; i < RIGHT; i++) {
InitArmSinglePolyhedron(i, &(*armPolyhedrons)[i],
offset_vec,
g_offset[i],
rotation);
addedOBBs_[simple][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[i],
collision_structures_[i].dimensions[0],
collision_structures_[i].dimensions[1],
collision_structures_[i].dimensions[2]);
}
offset_vec = g_origin[RIGHT];
for (int i = RIGHT; i < BASE; i++) {
InitArmSinglePolyhedron(i, &(*armPolyhedrons)[i],
offset_vec,
g_offset[i],
rotation);
addedOBBs_[simple][i] = gjk_interface::createOBBFromVertices((*armPolyhedrons)[i],
collision_structures_[i].dimensions[0],
collision_structures_[i].dimensions[1],
collision_structures_[i].dimensions[2]);
}
}
for (int i = LEFT_ARM_ORIGIN; i < BASE; ++i) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Link %d polyhedron points:", i);
for (int j = 0; j < POLYHEDRONS_POINTS_CNT; ++j) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%d: %.4f %.4f %.4f", j,
polyhedrons_[0][i][j].x(),
polyhedrons_[0][i][j].y(),
polyhedrons_[0][i][j].z());
}
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "---------------------");
for (int i = 0; i < maxObbCnt; i++) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "InitPolyhedronsList obb %d: center(%.2f, %.2f, %.2f), axis1(%.2f, %.2f, %.2f), axis2(%.2f, %.2f, %.2f), axis3(%.2f, %.2f, %.2f), half_lengths(%.2f, %.2f, %.2f)",
i,
addedOBBs_[0][i].center.x(), addedOBBs_[0][i].center.y(), addedOBBs_[0][i].center.z(),
addedOBBs_[0][i].axis[0].x(), addedOBBs_[0][i].axis[0].y(), addedOBBs_[0][i].axis[0].z(),
addedOBBs_[0][i].axis[1].x(), addedOBBs_[0][i].axis[1].y(), addedOBBs_[0][i].axis[1].z(),
addedOBBs_[0][i].axis[2].x(), addedOBBs_[0][i].axis[2].y(), addedOBBs_[0][i].axis[2].z(),
addedOBBs_[0][i].halfExtent[0], addedOBBs_[0][i].halfExtent[1], addedOBBs_[0][i].halfExtent[2]);
}
}
void CollisionSimulator::UpdateArmPolyhedrons()
int CollisionSimulator::CheckCollision()
{
std::vector<Polyhedron> *armPolyhedrons = &(polyhedrons_[simpleUpdateIndex_]);
UpdatePolyhedrons(LEFT_ARM_UPDATE_ORIGIN, RIGHT_ARM_ORIGIN, simpleUpdateIndex_,
joints_[simpleUpdateIndex_][BODY_TYPE_LEFT_ARM]);
UpdatePolyhedrons(RIGHT_ARM_UPDATE_ORIGIN, OTHER_ORIGIN, simpleUpdateIndex_,
joints_[simpleUpdateIndex_][BODY_TYPE_RIGHT_ARM]);
/*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 < POLYHEDRONS_POINTS_CNT; ++j) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "%d: %.4f %.4f %.4f", j,
polyhedrons_[0][i][j].x(),
polyhedrons_[0][i][j].y(),
polyhedrons_[0][i][j].z());
}
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "---------------------");
for (int bodyType = 0; bodyType < BODY_CNT; bodyType++) {
float *jointList = joints_[simpleUpdateIndex_][bodyType];
trajectory_[bodyType]->getAngleForChecking(jointList);
}
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)",
addedOBBs_[simple][i].center.x(),
addedOBBs_[simple][i].center.y(),
addedOBBs_[simple][i].center.z(),
addedOBBs_[simple][i].axis[0].x(),
addedOBBs_[simple][i].axis[0].y(),
addedOBBs_[simple][i].axis[0].z(),
addedOBBs_[simple][i].axis[1].x(),
addedOBBs_[simple][i].axis[1].y(),
addedOBBs_[simple][i].axis[1].z(),
addedOBBs_[simple][i].axis[2].x(),
addedOBBs_[simple][i].axis[2].y(),
addedOBBs_[simple][i].axis[2].z(),
addedOBBs_[simple][i].halfExtent[0],
addedOBBs_[simple][i].halfExtent[1],
addedOBBs_[simple][i].halfExtent[2]);
if (CheckJointsAngleLimit(simpleUpdateIndex_, BODY_TYPE_OTHERS) != 0) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "CheckCollision joints limit error.");
return ARM_AIM_CANNOT_REACH;
}
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "left joints: %.2f, %.2f, %.2f, %.2f, %.2f, %.2f",
leftArmJoints_[simple][0],
leftArmJoints_[simple][1],
leftArmJoints_[simple][2],
leftArmJoints_[simple][3],
leftArmJoints_[simple][4],
leftArmJoints_[simple][5]);*/
UpdatePolyhedrons(BODY_TYPE_OTHERS, simpleUpdateIndex_);
int lastSimpleIndex = (simpleUpdateIndex_ + COLLISION_CHECK_SIMPLE_CNT - 1) % COLLISION_CHECK_SIMPLE_CNT;
std::vector<OBB> *addedOBBsNext_ = &(addedOBBs_[simpleUpdateIndex_]);
std::vector<OBB> *addedOBBs = &(addedOBBs_[lastSimpleIndex]);
int result = CheckCollisionInner(addedOBBs, addedOBBsNext_);
simpleUpdateIndex_ = (simpleUpdateIndex_ + 1) % COLLISION_CHECK_SIMPLE_CNT;
return result;
}
int CollisionSimulator::AddPolyhedron(int id, const Polyhedron& poly)
@@ -463,19 +452,30 @@ int CollisionSimulator::RemovePolyhedron(int id)
return -1; // 未找到对应ID的多面体
}
int CollisionSimulator::CheckJointsAngleLimit(float *joints, int bodyType)
int CollisionSimulator::CheckJointsAngleLimit(int simple, int bodyType)
{
for (int i = 0; i < g_jointLinkCnt[bodyType]; ++i) {
JointInfo *joint = &(jointMap_[g_linkStartIndex[bodyType] + i]);
float angle = toRadians(joints[i]);
if (angle < joint->limit_lower || angle > joint->limit_upper) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()),
"CheckJointsAngleLimit: joint out of limit [%.4f, %.4f], current: %.4f(%.2f)",
joint->limit_lower, joint->limit_upper, angle, joints[i]);
CollisionStructureInfo *colStruct = &collision_structures_[g_linkStartIndex[bodyType]];
std::vector<JointsInfo *> 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++;
}
JointsInfo *jointInfo = jointList[index];
if (jointInfo->angle[simple][0] < jointInfo->limit_lower || jointInfo->angle[simple][0] > jointInfo->limit_upper) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "Joint %s angle limit error: %.2f not in [%.2f, %.2f]",
jointInfo->name.c_str(),
jointInfo->angle[simple][0],
jointInfo->limit_lower,
jointInfo->limit_upper);
return ARM_AIM_CANNOT_REACH;
}
index++;
colStruct = &collision_structures_[jointInfo->child_link];
}
return 0;
return OK;
}
int CollisionSimulator::UpdateCollisionForNewGoal(int bodyType)
@@ -484,19 +484,18 @@ int CollisionSimulator::UpdateCollisionForNewGoal(int bodyType)
int simple20 = (simpleUpdateIndex_ + 1) % COLLISION_CHECK_SIMPLE_CNT;
int simple40 = (simple20 + 1) % COLLISION_CHECK_SIMPLE_CNT;
int startLinkIndex = g_linkStartIndex[bodyType], endLinkIndex = startLinkIndex + g_jointLinkCnt[bodyType];
KinematicsManager *trajectory = trajectory_[bodyType];
float *jointList20 = joints_[simple20][bodyType];
float *jointList40 = joints_[simple40][bodyType];
trajectory->getAngleForStarting(jointList20);
trajectory->getAngleForChecking(jointList40);
if (CheckJointsAngleLimit(jointList20, bodyType) != 0 || CheckJointsAngleLimit(jointList40, bodyType) != 0) {
if (CheckJointsAngleLimit(simple20, bodyType) != 0 || CheckJointsAngleLimit(simple40, bodyType) != 0) {
RCLCPP_INFO(rclcpp::get_logger(GET_FUNC_LINE_STR()), "AngleDirectMove joints limit error.");
return ARM_AIM_CANNOT_REACH;
}
UpdatePolyhedrons(startLinkIndex, endLinkIndex, simple20, jointList20);
UpdatePolyhedrons(bodyType, simple20);
std::vector<OBB> *addedOBBsNext_ = &(addedOBBs_[simple20]);
std::vector<OBB> *addedOBBs = &(addedOBBs_[simpleUpdateIndex_]);
int result = CheckCollisionInner(addedOBBs, addedOBBsNext_);
@@ -505,7 +504,7 @@ int CollisionSimulator::UpdateCollisionForNewGoal(int bodyType)
return result;
}
UpdatePolyhedrons(startLinkIndex, endLinkIndex, simple40, jointList40);
UpdatePolyhedrons(bodyType, simple40);
addedOBBsNext_ = &(addedOBBs_[simple40]);
addedOBBs = &(addedOBBs_[simple20]);
result = CheckCollisionInner(addedOBBs, addedOBBsNext_);
@@ -515,72 +514,3 @@ int CollisionSimulator::UpdateCollisionForNewGoal(int bodyType)
}
return 0;
}
#include <rclcpp/rclcpp.hpp>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/collision_detection/collision_common.h>
int main(int argc, char**argv) {
// 初始化 ROS 节点
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("moveit_collision_demo");
// --------------------------
// 步骤1加载机器人模型创建 PlanningScene
// --------------------------
// 加载机器人模型(需在 launch 文件中加载 URDF 和 SRDF
robot_model_loader::RobotModelLoader robot_model_loader(node, "robot_description");
const moveit::core::RobotModelPtr& robot_model = robot_model_loader.getModel();
// 创建 PlanningScene管理碰撞环境
planning_scene::PlanningScene planning_scene(robot_model);
// --------------------------
// 步骤3定义机器人姿态待检测的状态
// --------------------------
moveit::core::RobotState& robot_state = planning_scene.getCurrentStateNonConst();
const moveit::core::JointModelGroup* joint_model_group = robot_state.getJointModelGroup("panda_arm"); // 机械臂组名称(需替换为你的机器人)
// 设置关节角度示例Panda 机械臂的一个姿态)
std::vector<double> joint_values = {0.0, 0.5, 0.0, -1.5, 0.0, 1.0, 0.0};
robot_state.setJointGroupPositions(joint_model_group, joint_values);
robot_state.update(); // 更新机器人状态
// --------------------------
// 步骤4调用碰撞检测接口
// --------------------------
// 定义碰撞检测请求(设置需要的结果类型)
collision_detection::CollisionRequest collision_request;
collision_request.contacts = true; // 是否返回接触信息(如碰撞点、法向量)
collision_request.max_contacts = 10; // 最大返回接触对数量
collision_request.max_contacts_per_pair = 3; // 每对碰撞体的最大接触点数量
collision_request.verbose = false; // 是否输出详细信息
// 存储碰撞检测结果
collision_detection::CollisionResult collision_result;
// 执行碰撞检测(检测机器人当前状态是否碰撞)
planning_scene.checkCollision(collision_request, collision_result);
// --------------------------
// 步骤5处理碰撞结果
// --------------------------
if (collision_result.collision) {
RCLCPP_WARN(node->get_logger(), "检测到碰撞!");
// 输出碰撞对信息(机器人关节/链接与障碍物的碰撞)
for (const auto& contact : collision_result.contacts) {
RCLCPP_INFO(node->get_logger(), "碰撞对: %s 与 %s",
contact.first.first.c_str(), // 第一个碰撞体ID
contact.first.second.c_str()); // 第二个碰撞体ID
}
} else {
RCLCPP_INFO(node->get_logger(), "未检测到碰撞。");
}
// 关闭节点
rclcpp::shutdown();
return 0;
}

View File

@@ -522,7 +522,6 @@ static bool GetMeshDimensions(const std::string& filename, CollisionStructure& c
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;
@@ -691,7 +690,7 @@ static int UpdateJointInfo(int i, int parent, Quaterniond &rotation, std::map<in
rotation = rotation * jointPair->second.rotation;
jointPair->second.rotationAll = rotation;
Eigen::Vector3d axis = jointPair->second.axis;
Vector3d axis = jointPair->second.axis;
g_dir[i] = rotation * axis;
return 0;
}

View File

@@ -1,8 +1,10 @@
#include "arm_define.h"
#include "rm_arm_simulator.hpp"
#include "rm_arm_node.hpp"
#include "col_simulator.hpp"
static ArmSimulator *armSimulator_;
static CollisionSimulator *colSimulator_;
using ArmGoalSharedPtr =
std::shared_ptr<const interfaces::action::Arm::Goal>;
@@ -132,6 +134,12 @@ RmArmNode::RmArmNode(ArmDriver *armDriver, Kinematics *kinematics) : Node("rm_ar
std::bind(&RmArmNode::ArmActionCancel, this, std::placeholders::_1),
std::bind(&RmArmNode::ArmActionAccepted, this, std::placeholders::_1));
this->declare_parameter<std::string>("robot_description_semantic", "");
std::string srdf_string = this->get_parameter("robot_description_semantic").as_string();
if (srdf_string == "") {
throw std::runtime_error("robot_description_semantic parameter is not valid.");
}
this->declare_parameter<std::string>("robot_description", "");
std::string urdf_string = this->get_parameter("robot_description").as_string();
/*leftArmHandler_->nowJoints_[0] = 180.0;
@@ -149,6 +157,10 @@ RmArmNode::RmArmNode(ArmDriver *armDriver, Kinematics *kinematics) : Node("rm_ar
armSimulator_ = new ArmSimulator(urdf_string, leftArmHandler_->nowJoints_, rightArmHandler_->nowJoints_,
leftArmHandler_->trapezoidalTrajectory_, rightArmHandler_->trapezoidalTrajectory_);
robotDescriptionSub_ = NULL;
/*colSimulator_ = new CollisionSimulator(urdf_string, srdf_string,
(float**)(std::vector<float*>{leftArmHandler_->nowJoints_, rightArmHandler_->nowJoints_}.data()),
(KinematicsManager**)(std::vector<KinematicsManager*>{leftArmHandler_->trapezoidalTrajectory_, rightArmHandler_->trapezoidalTrajectory_}.data()));*/
} else {
armSimulator_ = NULL;
robotDescriptionSub_ = this->create_subscription<std_msgs::msg::String>
@@ -176,9 +188,9 @@ void RmArmNode::CallbackGetRobotDescription(const std_msgs::msg::String::SharedP
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_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";
@@ -361,8 +373,12 @@ void RmArmNode::ArmActionCheck()
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
clock_gettime(CLOCK_REALTIME, &timeout);
timeout.tv_nsec += ARM_FOLLOWING_CHECKING;
if (timeout.tv_nsec >= 1e9) {
timeout.tv_sec += timeout.tv_nsec / (int64_t)(1e9);
timeout.tv_nsec = timeout.tv_nsec % (int64_t)(1e9);
}
int step = 0;
bool busy = false;
@@ -372,11 +388,13 @@ void RmArmNode::ArmActionCheck()
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_);
if (result == 0) {
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();
@@ -421,7 +439,11 @@ void RmArmNode::ArmActionCheck()
usedTime);
}
} else {
timeout.tv_nsec = nextCheckPoint - afterCheckTimeNs;
timeout.tv_nsec += nextCheckPoint - afterCheckTimeNs;
if (timeout.tv_nsec >= 1e9) {
timeout.tv_sec += timeout.tv_nsec / (int64_t)(1e9);
timeout.tv_nsec = timeout.tv_nsec % (int64_t)(1e9);
}
busy = false;
}
}