moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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 | |
RobotModelBuilder (const std::string &name, const std::string &base_link_name) | |
Constructor, takes the names of the robot and the base link. | |
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. | |
URDF Functions | |
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 "<parent>-<child>-joint". | |
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 | 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 | addVisualBox (const std::string &link_name, const std::vector< double > &size, geometry_msgs::msg::Pose origin) |
Adds a visual box to a specific link. | |
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) |
SRDF functions | |
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 | 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. | |
void | 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. | |
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 111 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 165 of file robot_model_test_utils.cpp.
void moveit::core::RobotModelBuilder::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 "<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 178 of file robot_model_test_utils.cpp.
void moveit::core::RobotModelBuilder::addCollisionBox | ( | const std::string & | link_name, |
const std::vector< double > & | dims, | ||
geometry_msgs::msg::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] | size | The dimensions of the box |
[in] | origin | The origin pose of this collision box relative to the link origin |
Definition at line 313 of file robot_model_test_utils.cpp.
void moveit::core::RobotModelBuilder::addCollisionMesh | ( | const std::string & | link_name, |
const std::string & | filename, | ||
geometry_msgs::msg::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 329 of file robot_model_test_utils.cpp.
void 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 431 of file robot_model_test_utils.cpp.
void 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 421 of file robot_model_test_utils.cpp.
void 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 406 of file robot_model_test_utils.cpp.
void moveit::core::RobotModelBuilder::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 | ||
) |
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 276 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 442 of file robot_model_test_utils.cpp.
void 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 388 of file robot_model_test_utils.cpp.
void moveit::core::RobotModelBuilder::addVisualBox | ( | const std::string & | link_name, |
const std::vector< double > & | size, | ||
geometry_msgs::msg::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 303 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 453 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 448 of file robot_model_test_utils.cpp.