40 #include <srdfdom/srdf_writer.h>
41 #include <urdf/model.h>
43 #include <geometry_msgs/msg/pose.hpp>
71 srdf::ModelSharedPtr
loadSRDFModel(
const std::string& robot_name);
106 void addChain(
const std::string& section,
const std::string&
type,
107 const std::vector<geometry_msgs::msg::Pose>& joint_origins = {},
108 urdf::Vector3 joint_axis = urdf::Vector3(1.0, 0.0, 0.0));
116 void addCollisionMesh(
const std::string& link_name,
const std::string& filename, geometry_msgs::msg::Pose origin);
122 void addCollisionBox(
const std::string& link_name,
const std::vector<double>& dims, geometry_msgs::msg::Pose origin);
129 void addVisualBox(
const std::string& link_name,
const std::vector<double>& size, geometry_msgs::msg::Pose origin);
137 void addInertial(
const std::string& link_name,
double mass, geometry_msgs::msg::Pose origin,
double ixx,
double ixy,
138 double ixz,
double iyy,
double iyz,
double izz);
152 void addVirtualJoint(
const std::string& parent_frame,
const std::string& child_link,
const std::string&
type,
153 const std::string&
name =
"");
160 void addGroupChain(
const std::string& base_link,
const std::string& tip_link,
const std::string&
name =
"");
167 void addGroup(
const std::vector<std::string>& links,
const std::vector<std::string>& joints,
const std::string&
name);
169 void addEndEffector(
const std::string&
name,
const std::string& parent_link,
const std::string& parent_group =
"",
170 const std::string& component_group =
"");
177 void addJointProperty(
const std::string& joint_name,
const std::string& property_name,
const std::string& value);
186 moveit::core::RobotModelPtr
build();
190 void addLinkCollision(
const std::string& link_name,
const urdf::CollisionSharedPtr& coll,
191 geometry_msgs::msg::Pose origin);
194 void addLinkVisual(
const std::string& link_name,
const urdf::VisualSharedPtr& vis, geometry_msgs::msg::Pose origin);
197 urdf::ModelInterfaceSharedPtr urdf_model_;
199 srdf::SRDFWriterPtr srdf_writer_;
202 bool is_valid_ =
true;
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
void addChain(const std::string §ion, 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.
RobotModelBuilder(const std::string &name, const std::string &base_link_name)
Constructor, takes the names of the robot and the base 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 &robot_name)
Loads a robot from moveit_resources.
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Main namespace for MoveIt.