moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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#if __has_include(<urdf/model.hpp>)
42#include <urdf/model.hpp>
43#else
44#include <urdf/model.h>
45#endif
47#include <geometry_msgs/msg/pose.hpp>
48
49#include <rclcpp/node.hpp>
50
51namespace moveit
52{
53namespace core
54{
55
62moveit::core::RobotModelPtr loadTestingRobotModel(const std::string& package_name,
63 const std::string& urdf_relative_path,
64 const std::string& srdf_relative_path);
65
72moveit::core::RobotModelPtr loadTestingRobotModel(const std::string& robot_name);
73
80urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string& robot_name);
81
88srdf::ModelSharedPtr loadSRDFModel(const std::string& robot_name);
89
97void loadIKPluginForGroup(const rclcpp::Node::SharedPtr& node, JointModelGroup* jmg, const std::string& base_link,
98 const std::string& tip_link, std::string plugin = "KDL", double timeout = 0.1);
99
112{
113public:
118 RobotModelBuilder(const std::string& name, const std::string& base_link_name);
119
133 void addChain(const std::string& section, const std::string& type,
134 const std::vector<geometry_msgs::msg::Pose>& joint_origins = {},
135 urdf::Vector3 joint_axis = urdf::Vector3(1.0, 0.0, 0.0));
136
143 void addCollisionMesh(const std::string& link_name, const std::string& filename, geometry_msgs::msg::Pose origin);
149 void addCollisionBox(const std::string& link_name, const std::vector<double>& dims, geometry_msgs::msg::Pose origin);
150
156 void addVisualBox(const std::string& link_name, const std::vector<double>& size, geometry_msgs::msg::Pose origin);
157
164 void addInertial(const std::string& link_name, double mass, geometry_msgs::msg::Pose origin, double ixx, double ixy,
165 double ixz, double iyy, double iyz, double izz);
166
179 void addVirtualJoint(const std::string& parent_frame, const std::string& child_link, const std::string& type,
180 const std::string& name = "");
181
187 void addGroupChain(const std::string& base_link, const std::string& tip_link, const std::string& name = "");
188
194 void addGroup(const std::vector<std::string>& links, const std::vector<std::string>& joints, const std::string& name);
195
196 void addEndEffector(const std::string& name, const std::string& parent_link, const std::string& parent_group = "",
197 const std::string& component_group = "");
198
204 void addJointProperty(const std::string& joint_name, const std::string& property_name, const std::string& value);
205
209 bool isValid();
210
213 moveit::core::RobotModelPtr build();
214
215private:
217 void addLinkCollision(const std::string& link_name, const urdf::CollisionSharedPtr& coll,
218 geometry_msgs::msg::Pose origin);
219
221 void addLinkVisual(const std::string& link_name, const urdf::VisualSharedPtr& vis, geometry_msgs::msg::Pose origin);
222
224 urdf::ModelInterfaceSharedPtr urdf_model_;
226 srdf::SRDFWriterPtr srdf_writer_;
227
229 bool is_valid_ = true;
230};
231} // namespace core
232} // namespace moveit
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
void addChain(const std::string &section, const std::string &type, const std::vector< geometry_msgs::msg::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...
void addInertial(const std::string &link_name, double mass, geometry_msgs::msg::Pose origin, double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
void addEndEffector(const std::string &name, const std::string &parent_link, const std::string &parent_group="", const std::string &component_group="")
void addCollisionBox(const std::string &link_name, const std::vector< double > &dims, geometry_msgs::msg::Pose origin)
Adds a collision box to a specific link.
void addJointProperty(const std::string &joint_name, const std::string &property_name, const std::string &value)
Adds a new joint property.
bool isValid()
Returns true if the building process so far has been valid.
void 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.
moveit::core::RobotModelPtr build()
Builds and returns the robot model added to the builder.
void 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.
void 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.
void addCollisionMesh(const std::string &link_name, const std::string &filename, geometry_msgs::msg::Pose origin)
Adds a collision mesh to a specific link.
void addVisualBox(const std::string &link_name, const std::vector< double > &size, geometry_msgs::msg::Pose origin)
Adds a visual box to a specific link.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
void loadIKPluginForGroup(const rclcpp::Node::SharedPtr &node, 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.
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Main namespace for MoveIt.
Definition exceptions.h:43