Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/robot_model/link_model.h>
00038 #include <moveit/robot_model/joint_model.h>
00039 #include <geometric_shapes/shape_operations.h>
00040
00041 moveit::core::LinkModel::LinkModel(const std::string &name)
00042 : name_(name)
00043 , parent_joint_model_(NULL)
00044 , parent_link_model_(NULL)
00045 , is_parent_joint_fixed_(false)
00046 , joint_origin_transform_is_identity_(true)
00047 , first_collision_body_transform_index_(-1)
00048 , link_index_(-1)
00049 {
00050 joint_origin_transform_.setIdentity();
00051 }
00052
00053 moveit::core::LinkModel::~LinkModel()
00054 {
00055 }
00056
00057 void moveit::core::LinkModel::setJointOriginTransform(const Eigen::Affine3d &transform)
00058 {
00059 joint_origin_transform_ = transform;
00060 joint_origin_transform_is_identity_ = joint_origin_transform_.rotation().isIdentity() &&
00061 joint_origin_transform_.translation().norm() < std::numeric_limits<double>::epsilon();
00062 }
00063
00064 void moveit::core::LinkModel::setParentJointModel(const JointModel *joint)
00065 {
00066 parent_joint_model_ = joint;
00067 is_parent_joint_fixed_ = joint->getType() == JointModel::FIXED;
00068 }
00069
00070 void moveit::core::LinkModel::setGeometry(const std::vector<shapes::ShapeConstPtr> &shapes, const EigenSTL::vector_Affine3d &origins)
00071 {
00072 shapes_ = shapes;
00073 collision_origin_transform_ = origins;
00074 collision_origin_transform_is_identity_.resize(collision_origin_transform_.size());
00075
00076 Eigen::Vector3d a = Eigen::Vector3d(0.0, 0.0, 0.0);
00077 Eigen::Vector3d b = Eigen::Vector3d(0.0, 0.0, 0.0);
00078
00079 for (std::size_t i = 0 ; i < shapes_.size() ; ++i)
00080 {
00081 collision_origin_transform_is_identity_[i] = (collision_origin_transform_[i].rotation().isIdentity() &&
00082 collision_origin_transform_[i].translation().norm() < std::numeric_limits<double>::epsilon()) ? 1 : 0;
00083 Eigen::Vector3d ei = shapes::computeShapeExtents(shapes_[i].get());
00084 Eigen::Vector3d p1 = collision_origin_transform_[i] * (-ei / 2.0);
00085 Eigen::Vector3d p2 = collision_origin_transform_[i] * (-p1);
00086
00087 if (i == 0)
00088 {
00089 a = p1;
00090 b = p2;
00091 }
00092 else
00093 {
00094 for (int i = 0 ; i < 3 ; ++i)
00095 a[i] = std::min(a[i], p1[i]);
00096 for (int i = 0 ; i < 3 ; ++i)
00097 b[i] = std::max(b[i], p2[i]);
00098 }
00099 }
00100
00101 shape_extents_ = b - a;
00102 }
00103
00104 void moveit::core::LinkModel::setVisualMesh(const std::string &visual_mesh, const Eigen::Affine3d &origin, const Eigen::Vector3d &scale)
00105 {
00106 visual_mesh_filename_ = visual_mesh;
00107 visual_mesh_origin_ = origin;
00108 visual_mesh_scale_ = scale;
00109 }