Go to the documentation of this file.
43 #include <geometry_msgs/Pose.h>
80 void loadIKPluginForGroup(JointModelGroup* jmg,
const std::string& base_link,
const std::string& tip_link,
81 std::string plugin =
"KDL",
double timeout = 0.1);
94 class RobotModelBuilder
117 const std::vector<geometry_msgs::Pose>& joint_origins = {},
118 urdf::Vector3 joint_axis = urdf::Vector3(1.0, 0.0, 0.0));
127 geometry_msgs::Pose origin);
142 geometry_msgs::Pose origin);
150 geometry_msgs::Pose origin);
159 double ixy,
double ixz,
double iyy,
double iyz,
double izz);
174 const std::string& type,
const std::string& name =
"");
182 const std::string& name =
"");
190 const std::string& name);
193 const std::string& parent_group =
"",
const std::string& component_group =
"");
200 void addJointProperty(
const std::string& joint_name,
const std::string& property_name,
const std::string& value);
209 moveit::core::RobotModelPtr
build();
213 void addLinkCollision(
const std::string& link_name,
const urdf::CollisionSharedPtr& coll, geometry_msgs::Pose origin);
216 void addLinkVisual(
const std::string& link_name,
const urdf::VisualSharedPtr& vis, geometry_msgs::Pose origin);
bool is_valid_
Whether the current builder state is valid. If any 'add' method fails, this becomes false.
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.
RobotModelBuilder & addVisualBox(const std::string &link_name, const std::vector< double > &size, geometry_msgs::Pose origin)
Adds a visual 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.
void addLinkVisual(const std::string &link_name, const urdf::VisualSharedPtr &vis, geometry_msgs::Pose origin)
Adds different visual geometries to a link.
RobotModelBuilder & addCollisionMesh(const std::string &link_name, const std::string &filename, geometry_msgs::Pose origin)
Adds a collision mesh to a specific link.
std::shared_ptr< Model > ModelSharedPtr
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)
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
RobotModelBuilder & addCollisionBox(const std::string &link_name, const std::vector< double > &dims, geometry_msgs::Pose origin)
Adds a collision box to a specific link.
urdf::ModelInterfaceSharedPtr urdf_model_
The URDF model, holds all of the URDF components of the robot added so far.
bool isValid()
Returns true if the building process so far has been valid.
moveit::core::RobotModelPtr build()
Builds and returns the robot model added to the builder.
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.
srdf::ModelSharedPtr loadSRDFModel(const std::string &robot_name)
Loads an SRDF Model from moveit_resources.
void addLinkCollision(const std::string &link_name, const urdf::CollisionSharedPtr &coll, geometry_msgs::Pose origin)
Adds different collision geometries to a link.
RobotModelBuilder & addCollisionSphere(const std::string &link_name, double dims, geometry_msgs::Pose origin)
Adds a collision sphere 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.
Main namespace for MoveIt.
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
RobotModelBuilder & addChain(const std::string §ion, 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...
RobotModelBuilder & addEndEffector(const std::string &name, const std::string &parent_link, const std::string &parent_group="", const std::string &component_group="")
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.
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.
srdf::SRDFWriterPtr srdf_writer_
The SRDF model, holds all of the SRDF components of the robot added so far.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
std::shared_ptr< SRDFWriter > SRDFWriterPtr
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15