29 const std::string& ee_name,
30 const std::vector<std::string>& joint_names,
31 const pinocchio::GeometryModel& collision_model,
32 const pinocchio::GeometryModel& visual_model)
33 : model_(model), data_(model), collision_model_(collision_model), visual_model_(visual_model)
36 if (
model_.existFrame(ee_name)){
40 throw std::invalid_argument(
"The targeted end-effector frame [" + ee_name +
"] does not exist in the model.");
45 for (
const auto& joint_name : joint_names)
47 if(model.existFrame(joint_name)){
51 throw std::invalid_argument(
"The joint name [" + joint_name +
"] does not exist in the model.");
124 const std::vector<obstacleInput>& obstacles,
125 std::vector<distanceResult>& distances)
132 int robot_geom_num = geom_model.ngeoms;
134 geom_model.removeAllCollisionPairs();
139 for (
const auto& obstacle : obstacles)
142 pinocchio::GeometryObject::CollisionGeometryPtr collision_geometry;
143 std::string mesh_path =
"";
144 Eigen::Vector3d mesh_scale = Eigen::Vector3d::Ones();
146 std::visit([&collision_geometry, &mesh_path, &mesh_scale](
auto&& arg) {
147 using T = std::decay_t<
decltype(arg)>;
148 if constexpr (std::is_same_v<T, coal::Sphere>) {
149 collision_geometry = std::make_shared<coal::Sphere>(arg);
150 mesh_path =
"SPHERE";
151 mesh_scale = Eigen::Vector3d::Ones() * arg.radius;
153 }, obstacle.obstacle);
155 pinocchio::GeometryObject geom_object(
156 "Obstacle_" + std::to_string(i_obstacle),
158 pinocchio::SE3(obstacle.obstacle_pose),
163 Eigen::Vector4d(0.5, 0.5, 0.5, 1.0)
167 geom_model.addGeometryObject(geom_object);
172 for(
int i = 0; i < robot_geom_num; i++){
173 if(geom_model.geometryObjects[i].disableCollision ==
false){
174 geom_model.addCollisionPair(pinocchio::CollisionPair(robot_geom_num + i_obstacle, i));
182 pinocchio::GeometryData geom_data(geom_model);
185 pinocchio::updateGeometryPlacements(
model_,
data_, geom_model, geom_data);
186 pinocchio::computeDistances(geom_model, geom_data);
189 for (
int i = 0; i < geom_data.distanceResults.size(); i++)
191 const auto& distance = geom_data.distanceResults[i];
192 const auto& robot_geom = geom_model.geometryObjects[geom_model.collisionPairs[i].second];
193 Eigen::Vector3d seperation_vector = (distance.nearest_points[1] - distance.nearest_points[0]).normalized();
194 Eigen::MatrixXd jacobian_matrix;
195 this->
jacobianFrame(q, robot_geom.parentFrame, jacobian_matrix);
196 Eigen::VectorXd projector_control_to_dist = seperation_vector.transpose() * jacobian_matrix.topRows(3);
197 Eigen::VectorXd projector_dist_to_control;
200 projector_dist_to_control = (1.0 / projector_control_to_dist.norm() / projector_control_to_dist.norm()) * projector_control_to_dist.transpose();
203 Eigen::VectorXd seperation_twist = Eigen::VectorXd::Zero(6);
204 seperation_twist.head(3) = seperation_vector;
205 Eigen::MatrixXd JJt = jacobian_matrix * jacobian_matrix.transpose();
208 projector_dist_to_control = jacobian_matrix.transpose() * (JJt + damped_identity).ldlt().solve(seperation_twist);
209 projector_control_to_dist = (1.0 / projector_dist_to_control.norm() * projector_dist_to_control.norm()) * projector_dist_to_control.transpose();
215 distance.min_distance,
217 distance.nearest_points[1],
218 distance.nearest_points[0],
220 projector_control_to_dist,
221 projector_dist_to_control