Easily build different robot models for testing. Essentially a programmer-friendly light wrapper around URDF and SRDF. Best shown by an example: More...
#include <robot_model_test_utils.h>
Public Member Functions | |
moveit::core::RobotModelPtr | build () |
Builds and returns the robot model added to the builder. More... | |
bool | isValid () |
Returns true if the building process so far has been valid. More... | |
RobotModelBuilder (const std::string &name, const std::string &base_link_name) | |
Constructor, takes the names of the robot and the base link. More... | |
URDF Functions | |
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 "<parent>-<child>-joint". More... | |
RobotModelBuilder & | addCollisionMesh (const std::string &link_name, const std::string &filename, geometry_msgs::Pose origin) |
Adds a collision mesh to a specific link. More... | |
RobotModelBuilder & | addCollisionSphere (const std::string &link_name, double dims, geometry_msgs::Pose origin) |
Adds a collision sphere to a specific link. More... | |
RobotModelBuilder & | addCollisionBox (const std::string &link_name, const std::vector< double > &dims, geometry_msgs::Pose origin) |
Adds a collision box to a specific link. More... | |
RobotModelBuilder & | addVisualBox (const std::string &link_name, const std::vector< double > &size, geometry_msgs::Pose origin) |
Adds a visual box to a specific link. More... | |
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) |
SRDF functions | |
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. More... | |
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. More... | |
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. More... | |
RobotModelBuilder & | addEndEffector (const std::string &name, const std::string &parent_link, const std::string &parent_group="", const std::string &component_group="") |
void | addJointProperty (const std::string &joint_name, const std::string &property_name, const std::string &value) |
Adds a new joint property. More... | |
Private Member Functions | |
void | addLinkCollision (const std::string &link_name, const urdf::CollisionSharedPtr &coll, geometry_msgs::Pose origin) |
Adds different collision geometries to a link. More... | |
void | addLinkVisual (const std::string &link_name, const urdf::VisualSharedPtr &vis, geometry_msgs::Pose origin) |
Adds different visual geometries to a link. More... | |
Private Attributes | |
bool | is_valid_ = true |
Whether the current builder state is valid. If any 'add' method fails, this becomes false. More... | |
srdf::SRDFWriterPtr | srdf_writer_ |
The SRDF model, holds all of the SRDF components of the robot added so far. More... | |
urdf::ModelInterfaceSharedPtr | urdf_model_ |
The URDF model, holds all of the URDF components of the robot added so far. More... | |
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper around URDF and SRDF. Best shown by an example:
Definition at line 158 of file robot_model_test_utils.h.
moveit::core::RobotModelBuilder::RobotModelBuilder | ( | const std::string & | name, |
const std::string & | base_link_name | ||
) |
Constructor, takes the names of the robot and the base link.
[in] | name | The name of the robot, i.e. the 'name' attribute of the robot tag in URDF |
[in] | base_link_name | The name of the root link of the robot. All other links should be descendants of this |
Definition at line 191 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::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 "<parent>-<child>-joint".
[in] | section | A list of link names separated by "->". The first link should already be added to the build by the time this function is called |
[in] | type | The type of the joints connecting all of the given links, e.g. "revolute" or "continuous". All of the joints will be given this type. To add multiple types of joints, call this method multiple times |
[in] | joint_origins | The "parent to joint" origins for the joints connecting the links. If not used, all origins will default to the identity transform |
[in] | joint_axis | The joint axis specified in the joint frame defaults to (1,0,0) |
Definition at line 204 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::RobotModelBuilder::addCollisionBox | ( | const std::string & | link_name, |
const std::vector< double > & | dims, | ||
geometry_msgs::Pose | origin | ||
) |
Adds a collision box to a specific link.
[in] | link_name | The name of the link to which the box will be added. Must already be in the builder. |
[in] | dims | The dimensions of the box |
[in] | origin | The origin pose of this collision box relative to the link origin |
Definition at line 344 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::RobotModelBuilder::addCollisionMesh | ( | const std::string & | link_name, |
const std::string & | filename, | ||
geometry_msgs::Pose | origin | ||
) |
Adds a collision mesh to a specific link.
[in] | link_name | The name of the link to which the mesh will be added. Must already be in the builder |
[in] | filename | The path to the mesh file, e.g. "package://moveit_resources_pr2_description/urdf/meshes/base_v0/base_L.stl" |
[in] | origin | The origin pose of this collision mesh relative to the link origin |
Definition at line 361 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::RobotModelBuilder::addCollisionSphere | ( | const std::string & | link_name, |
double | dims, | ||
geometry_msgs::Pose | origin | ||
) |
Adds a collision sphere to a specific link.
[in] | link_name | The name of the link to which the sphere will be added. Must already be in the builder. |
[in] | radius | The radius of the sphere |
[in] | origin | The origin pose of this collision sphere relative to the link origin |
Definition at line 333 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::RobotModelBuilder::addEndEffector | ( | const std::string & | name, |
const std::string & | parent_link, | ||
const std::string & | parent_group = "" , |
||
const std::string & | component_group = "" |
||
) |
Definition at line 460 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::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.
[in] | links | The links (really their parent joints) to include in the group |
[in] | joints | The joints to include in the group |
[in] | name | The name of the group, required |
Definition at line 449 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::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.
[in] | base_link | The starting link of the chain |
[in] | tip_link | The ending link of the chain. |
[in] | name | The name of the group, if not given it's set as "<base>-<tip>-chain-group" |
Definition at line 436 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::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 | ||
) |
Adds an inertial component to a link.
[in] | link_name | The name of the link for this inertial information |
[in] | mass | The mass of the link |
[in] | origin | The origin center pose of the center of mass of this link |
Definition at line 292 of file robot_model_test_utils.cpp.
void moveit::core::RobotModelBuilder::addJointProperty | ( | const std::string & | joint_name, |
const std::string & | property_name, | ||
const std::string & | value | ||
) |
Adds a new joint property.
[in] | joint_name | The name of the joint the property is specified for |
[in] | property_name | The joint property name |
[in] | value | The value of the joint property |
Definition at line 473 of file robot_model_test_utils.cpp.
|
private |
Adds different collision geometries to a link.
Definition at line 372 of file robot_model_test_utils.cpp.
|
private |
Adds different visual geometries to a link.
Definition at line 390 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::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.
[in] | parent_frame | The parent, e.g. "odom" |
[in] | child_link | The child link of this virtual joint, usually the base link |
[in] | type | The type of joint, can be "fixed", "floating", or "planar" |
[in] | name | The name of the virtual joint, if not given it's automatically made to be "<parent_frame>-<child>-virtual-joint" |
Definition at line 421 of file robot_model_test_utils.cpp.
RobotModelBuilder & moveit::core::RobotModelBuilder::addVisualBox | ( | const std::string & | link_name, |
const std::vector< double > & | size, | ||
geometry_msgs::Pose | origin | ||
) |
Adds a visual box to a specific link.
[in] | link_name | The name of the link to which the box will be added. Must already be in the builder. |
[in] | size | The dimensions of the box |
[in] | origin | The origin pose of this visual box relative to the link origin |
Definition at line 322 of file robot_model_test_utils.cpp.
moveit::core::RobotModelPtr moveit::core::RobotModelBuilder::build | ( | ) |
Builds and returns the robot model added to the builder.
Definition at line 484 of file robot_model_test_utils.cpp.
bool moveit::core::RobotModelBuilder::isValid | ( | ) |
Returns true if the building process so far has been valid.
Definition at line 479 of file robot_model_test_utils.cpp.
|
private |
Whether the current builder state is valid. If any 'add' method fails, this becomes false.
Definition at line 288 of file robot_model_test_utils.h.
|
private |
The SRDF model, holds all of the SRDF components of the robot added so far.
Definition at line 285 of file robot_model_test_utils.h.
|
private |
The URDF model, holds all of the URDF components of the robot added so far.
Definition at line 283 of file robot_model_test_utils.h.