robot_model_test_utils.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Bryce Willey.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of MoveIt nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Bryce Willey */
38 #pragma once
39 
40 #include <srdfdom/srdf_writer.h>
41 #include <urdf/model.h>
43 #include <geometry_msgs/Pose.h>
44 
45 namespace moveit
46 {
47 namespace core
48 {
55 moveit::core::RobotModelPtr loadTestingRobotModel(const std::string& robot_name);
56 
63 urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string& robot_name);
64 
71 srdf::ModelSharedPtr loadSRDFModel(const std::string& robot_name);
72 
80 void loadIKPluginForGroup(JointModelGroup* jmg, const std::string& base_link, const std::string& tip_link,
81  std::string plugin = "KDL", double timeout = 0.1);
82 
94 class RobotModelBuilder
95 {
96 public:
101  RobotModelBuilder(const std::string& name, const std::string& base_link_name);
102 
116  RobotModelBuilder& addChain(const std::string& section, const std::string& type,
117  const std::vector<geometry_msgs::Pose>& joint_origins = {},
118  urdf::Vector3 joint_axis = urdf::Vector3(1.0, 0.0, 0.0));
119 
126  RobotModelBuilder& addCollisionMesh(const std::string& link_name, const std::string& filename,
127  geometry_msgs::Pose origin);
128 
134  RobotModelBuilder& addCollisionSphere(const std::string& link_name, double dims, geometry_msgs::Pose origin);
135 
141  RobotModelBuilder& addCollisionBox(const std::string& link_name, const std::vector<double>& dims,
142  geometry_msgs::Pose origin);
143 
149  RobotModelBuilder& addVisualBox(const std::string& link_name, const std::vector<double>& size,
150  geometry_msgs::Pose origin);
151 
158  RobotModelBuilder& addInertial(const std::string& link_name, double mass, geometry_msgs::Pose origin, double ixx,
159  double ixy, double ixz, double iyy, double iyz, double izz);
160 
173  RobotModelBuilder& addVirtualJoint(const std::string& parent_frame, const std::string& child_link,
174  const std::string& type, const std::string& name = "");
175 
181  RobotModelBuilder& addGroupChain(const std::string& base_link, const std::string& tip_link,
182  const std::string& name = "");
183 
189  RobotModelBuilder& addGroup(const std::vector<std::string>& links, const std::vector<std::string>& joints,
190  const std::string& name);
191 
192  RobotModelBuilder& addEndEffector(const std::string& name, const std::string& parent_link,
193  const std::string& parent_group = "", const std::string& component_group = "");
194 
200  void addJointProperty(const std::string& joint_name, const std::string& property_name, const std::string& value);
201 
205  bool isValid();
206 
209  moveit::core::RobotModelPtr build();
210 
211 private:
213  void addLinkCollision(const std::string& link_name, const urdf::CollisionSharedPtr& coll, geometry_msgs::Pose origin);
214 
216  void addLinkVisual(const std::string& link_name, const urdf::VisualSharedPtr& vis, geometry_msgs::Pose origin);
217 
219  urdf::ModelInterfaceSharedPtr urdf_model_;
222 
224  bool is_valid_ = true;
225 };
226 } // namespace core
227 } // namespace moveit
moveit::core::RobotModelBuilder::is_valid_
bool is_valid_
Whether the current builder state is valid. If any 'add' method fails, this becomes false.
Definition: robot_model_test_utils.h:288
moveit::core::RobotModelBuilder::addGroupChain
RobotModelBuilder & addGroupChain(const std::string &base_link, const std::string &tip_link, const std::string &name="")
Adds a new group using a chain of links. The group is the parent joint of each link in the chain.
Definition: robot_model_test_utils.cpp:436
moveit::core::RobotModelBuilder::addVisualBox
RobotModelBuilder & addVisualBox(const std::string &link_name, const std::vector< double > &size, geometry_msgs::Pose origin)
Adds a visual box to a specific link.
Definition: robot_model_test_utils.cpp:322
moveit::core::RobotModelBuilder::addJointProperty
void addJointProperty(const std::string &joint_name, const std::string &property_name, const std::string &value)
Adds a new joint property.
Definition: robot_model_test_utils.cpp:473
moveit::core::RobotModelBuilder::addLinkVisual
void addLinkVisual(const std::string &link_name, const urdf::VisualSharedPtr &vis, geometry_msgs::Pose origin)
Adds different visual geometries to a link.
Definition: robot_model_test_utils.cpp:390
moveit::core::RobotModelBuilder::addCollisionMesh
RobotModelBuilder & addCollisionMesh(const std::string &link_name, const std::string &filename, geometry_msgs::Pose origin)
Adds a collision mesh to a specific link.
Definition: robot_model_test_utils.cpp:361
srdf::ModelSharedPtr
std::shared_ptr< Model > ModelSharedPtr
moveit::core::RobotModelBuilder::addInertial
RobotModelBuilder & addInertial(const std::string &link_name, double mass, geometry_msgs::Pose origin, double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
Definition: robot_model_test_utils.cpp:292
moveit::core::loadModelInterface
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Definition: robot_model_test_utils.cpp:126
robot_model.h
moveit::core::RobotModelBuilder::addCollisionBox
RobotModelBuilder & addCollisionBox(const std::string &link_name, const std::vector< double > &dims, geometry_msgs::Pose origin)
Adds a collision box to a specific link.
Definition: robot_model_test_utils.cpp:344
moveit::core::RobotModelBuilder::urdf_model_
urdf::ModelInterfaceSharedPtr urdf_model_
The URDF model, holds all of the URDF components of the robot added so far.
Definition: robot_model_test_utils.h:283
model.h
moveit::core::RobotModelBuilder::isValid
bool isValid()
Returns true if the building process so far has been valid.
Definition: robot_model_test_utils.cpp:479
moveit::core::RobotModelBuilder::build
moveit::core::RobotModelPtr build()
Builds and returns the robot model added to the builder.
Definition: robot_model_test_utils.cpp:484
moveit::core::RobotModelBuilder::addVirtualJoint
RobotModelBuilder & addVirtualJoint(const std::string &parent_frame, const std::string &child_link, const std::string &type, const std::string &name="")
Adds a virtual joint to the SRDF.
Definition: robot_model_test_utils.cpp:421
moveit::core::loadSRDFModel
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
Definition: robot_model_test_utils.cpp:147
moveit::core::RobotModelBuilder::addLinkCollision
void addLinkCollision(const std::string &link_name, const urdf::CollisionSharedPtr &coll, geometry_msgs::Pose origin)
Adds different collision geometries to a link.
Definition: robot_model_test_utils.cpp:372
moveit::core::RobotModelBuilder::addCollisionSphere
RobotModelBuilder & addCollisionSphere(const std::string &link_name, double dims, geometry_msgs::Pose origin)
Adds a collision sphere to a specific link.
Definition: robot_model_test_utils.cpp:333
moveit::core::RobotModelBuilder::RobotModelBuilder
RobotModelBuilder(const std::string &name, const std::string &base_link_name)
Constructor, takes the names of the robot and the base link.
Definition: robot_model_test_utils.cpp:191
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
moveit::core::RobotModelBuilder
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
Definition: robot_model_test_utils.h:158
moveit::core::RobotModelBuilder::addChain
RobotModelBuilder & addChain(const std::string &section, const std::string &type, const std::vector< geometry_msgs::Pose > &joint_origins={}, urdf::Vector3 joint_axis=urdf::Vector3(1.0, 0.0, 0.0))
Adds a chain of links and joints to the builder. The joint names are generated automatically as "<par...
Definition: robot_model_test_utils.cpp:204
moveit::core::RobotModelBuilder::addEndEffector
RobotModelBuilder & addEndEffector(const std::string &name, const std::string &parent_link, const std::string &parent_group="", const std::string &component_group="")
Definition: robot_model_test_utils.cpp:460
srdf_writer.h
moveit::core::loadIKPluginForGroup
void loadIKPluginForGroup(JointModelGroup *jmg, const std::string &base_link, const std::string &tip_link, std::string plugin="KDL", double timeout=0.1)
Load an IK solver plugin for the given joint model group.
Definition: robot_model_test_utils.cpp:165
moveit::core::RobotModelBuilder::addGroup
RobotModelBuilder & addGroup(const std::vector< std::string > &links, const std::vector< std::string > &joints, const std::string &name)
Adds a new group using a list of links and a list of joints.
Definition: robot_model_test_utils.cpp:449
moveit::core::RobotModelBuilder::srdf_writer_
srdf::SRDFWriterPtr srdf_writer_
The SRDF model, holds all of the SRDF components of the robot added so far.
Definition: robot_model_test_utils.h:285
moveit::core::loadTestingRobotModel
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
Definition: robot_model_test_utils.cpp:117
srdf::SRDFWriterPtr
std::shared_ptr< SRDFWriter > SRDFWriterPtr


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:40