Classes | |
class | Parser |
Parse an URDF file and return a hpp::model::HumanoidRobotPtr_t. More... | |
Functions | |
void | loadRobotModel (const DevicePtr_t &robot, const JointPtr_t &baseJoint, const std::string &prefix, const std::string &rootJointType, const std::string &package, const std::string &modelName, const std::string &urdfSuffix, const std::string &srdfSuffix) |
Load robot model by name. | |
void | loadRobotModel (const DevicePtr_t &robot, const std::string &rootJointType, const std::string &package, const std::string &modelName, const std::string &urdfSuffix, const std::string &srdfSuffix) |
void | loadRobotModelFromParameter (const DevicePtr_t &robot, const std::string &rootJointType, const std::string &urdfParameter, const std::string &srdfParameter) |
Load robot model from ROS parameter. | |
void | loadHumanoidModel (const model::HumanoidRobotPtr_t &robot, const JointPtr_t &baseJoint, const std::string &prefix, const std::string &rootJointType, const std::string &package, const std::string &modelName, const std::string &urdfSuffix, const std::string &srdfSuffix) |
Load humanoid robot model by name. | |
void | loadHumanoidModel (const model::HumanoidRobotPtr_t &robot, const std::string &rootJointType, const std::string &package, const std::string &modelName, const std::string &urdfSuffix, const std::string &srdfSuffix) |
void | loadHumanoidModelFromParameter (const model::HumanoidRobotPtr_t &robot, const std::string &rootJointType, const std::string &urdfParameter, const std::string &srdfParameter) |
Load humanoid robot model from ROS parameter. | |
void | loadUrdfModel (const DevicePtr_t &robot, const JointPtr_t &baseJoint, const std::string &prefix, const std::string &rootJointType, const std::string &package, const std::string &filename) |
Load only urdf model file. | |
void | loadUrdfModel (const DevicePtr_t &robot, const std::string &rootJointType, const std::string &package, const std::string &filename) |
void hpp::model::urdf::loadHumanoidModel | ( | const model::HumanoidRobotPtr_t & | robot, |
const JointPtr_t & | baseJoint, | ||
const std::string & | prefix, | ||
const std::string & | rootJointType, | ||
const std::string & | package, | ||
const std::string & | modelName, | ||
const std::string & | urdfSuffix, | ||
const std::string & | srdfSuffix | ||
) |
Load humanoid robot model by name.
robot | Empty robot created before calling the function. Users can pass an instance of a class deriving from HumanoidRobot. |
baseJoint | joint to which the joint tree is added. |
prefix | string to insert before all names (joint, link, body names) |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
package | ros package containing the model |
modelName | robot model name |
urdfSuffix | suffix for urdf file |
srdfSuffix | suffix for srdf file |
void hpp::model::urdf::loadHumanoidModel | ( | const model::HumanoidRobotPtr_t & | robot, |
const std::string & | rootJointType, | ||
const std::string & | package, | ||
const std::string & | modelName, | ||
const std::string & | urdfSuffix, | ||
const std::string & | srdfSuffix | ||
) |
void hpp::model::urdf::loadHumanoidModelFromParameter | ( | const model::HumanoidRobotPtr_t & | robot, |
const std::string & | rootJointType, | ||
const std::string & | urdfParameter, | ||
const std::string & | srdfParameter | ||
) |
Load humanoid robot model from ROS parameter.
robot | Empty robot created before calling the function. Users can pass an instance of a class deriving from Device. |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfParameter | Parameter containing the urdf description of the robot |
srdfParameter | Parameter containing the srdf description of the robot |
void hpp::model::urdf::loadRobotModel | ( | const DevicePtr_t & | robot, |
const JointPtr_t & | baseJoint, | ||
const std::string & | prefix, | ||
const std::string & | rootJointType, | ||
const std::string & | package, | ||
const std::string & | modelName, | ||
const std::string & | urdfSuffix, | ||
const std::string & | srdfSuffix | ||
) |
Load robot model by name.
robot | Empty robot created before calling the function. Users can pass an instance of a class deriving from Device. |
baseJoint | joint to which the joint tree is added. |
prefix | string to insert before all names (joint, link, body names) |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
package | ros package containing the model |
modelName | robot model name |
urdfSuffix | suffix for urdf file |
srdfSuffix | suffix for srdf file |
void hpp::model::urdf::loadRobotModel | ( | const DevicePtr_t & | robot, |
const std::string & | rootJointType, | ||
const std::string & | package, | ||
const std::string & | modelName, | ||
const std::string & | urdfSuffix, | ||
const std::string & | srdfSuffix | ||
) |
void hpp::model::urdf::loadRobotModelFromParameter | ( | const DevicePtr_t & | robot, |
const std::string & | rootJointType, | ||
const std::string & | urdfParameter, | ||
const std::string & | srdfParameter | ||
) |
Load robot model from ROS parameter.
robot | Empty robot created before calling the function. Users can pass an instance of a class deriving from Device. |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
urdfParameter | Parameter containing the urdf description of the robot |
srdfParameter | Parameter containing the srdf description of the robot |
void hpp::model::urdf::loadUrdfModel | ( | const DevicePtr_t & | robot, |
const JointPtr_t & | baseJoint, | ||
const std::string & | prefix, | ||
const std::string & | rootJointType, | ||
const std::string & | package, | ||
const std::string & | filename | ||
) |
Load only urdf model file.
robot | Empty robot created before calling the function. Users can pass an instance of a class deriving from Device. |
baseJoint | joint to which the joint tree is added. |
prefix | string to insert before all names (joint, link, body names) |
rootJointType | type of root joint among "anchor", "freeflyer", "planar", |
package | ros package containing the model |
filename | name of the file containing the model. |
void hpp::model::urdf::loadUrdfModel | ( | const DevicePtr_t & | robot, |
const std::string & | rootJointType, | ||
const std::string & | package, | ||
const std::string & | filename | ||
) |