43 parent_node_->declare_parameter(
"robot_description_semantic", rclcpp::ParameterType::PARAMETER_STRING);
51 throw std::runtime_error(
"cannot find relative_path property in SRDF");
73 parent_node_->set_parameter(rclcpp::Parameter(
"robot_description_semantic",
srdf_.getSRDFString()));
79 loadSRDFFile(std::filesystem::path(package_path) / relative_path);
90 std::string srdf_string;
93 throw std::runtime_error(
"SRDF file not found: " +
srdf_path_.string());
99 throw std::runtime_error(
"SRDF file not a valid semantic robot description model.");
103 parent_node_->set_parameter(rclcpp::Parameter(
"robot_description_semantic", srdf_string));
107 RCLCPP_INFO_STREAM(*
logger_,
"Robot semantic model successfully loaded.");
123 if (changed_information > 0)
160 std::vector<std::string> names;
163 names.push_back(link_model->getName());
181 for (std::vector<srdf::Model::GroupState>::iterator pose_it =
srdf_.group_states_.begin();
182 pose_it !=
srdf_.group_states_.end(); ++pose_it)
184 if (pose_it->name_ == pose_name && pose_it->group_ == group_name)
186 srdf_.group_states_.erase(pose_it);
194 bool include_passive)
196 std::vector<std::string> names;
202 if (!include_multi_dof && joint->getVariableCount() > 1)
206 else if (!include_passive && joint->isPassive())
210 names.push_back(joint->getName());
238 emitter << YAML::Comment(
"joint_limits.yaml allows the dynamics properties specified in the URDF "
239 "to be overwritten or augmented as needed");
240 emitter << YAML::Newline;
242 emitter << YAML::BeginMap;
244 emitter << YAML::Comment(
"For beginners, we downscale velocity and acceleration limits.") << YAML::Newline;
245 emitter << YAML::Comment(
"You can always specify higher scaling factors (<= 1.0) in your motion requests.");
246 emitter << YAML::Comment(
"Increase the values below to 1.0 to always move at maximum speed.");
247 emitter << YAML::Key <<
"default_velocity_scaling_factor";
248 emitter << YAML::Value <<
"0.1";
250 emitter << YAML::Key <<
"default_acceleration_scaling_factor";
251 emitter << YAML::Value <<
"0.1";
253 emitter << YAML::Newline << YAML::Newline;
254 emitter << YAML::Comment(
"Specific joint properties can be changed with the keys "
255 "[max_position, min_position, max_velocity, max_acceleration]")
257 emitter << YAML::Comment(
"Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]");
259 emitter << YAML::Key <<
"joint_limits";
260 emitter << YAML::Value << YAML::BeginMap;
263 std::set<const moveit::core::JointModel*, JointModelCompare> joints;
271 const std::vector<const moveit::core::JointModel*>& joint_models = joint_model_group->
getJointModels();
277 if (joint_model->getVariableCount() == 1)
278 joints.insert(joint_model);
285 emitter << YAML::Key << joint->getName();
286 emitter << YAML::Value << YAML::BeginMap;
291 emitter << YAML::Key <<
"has_velocity_limits";
293 emitter << YAML::Value <<
"true";
295 emitter << YAML::Value <<
"false";
298 emitter << YAML::Key <<
"max_velocity";
302 emitter << YAML::Key <<
"has_acceleration_limits";
304 emitter << YAML::Value <<
"true";
306 emitter << YAML::Value <<
"false";
309 emitter << YAML::Key <<
"max_acceleration";
312 emitter << YAML::EndMap;
315 emitter << YAML::EndMap;
321 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
const std::string & getName() const
Get the name of the joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
const std::string & getName() const
The name of this link.
bool writeYaml(YAML::Emitter &emitter) override
void updateRobotModel(long changed_information=0L)
srdf::SRDFWriter srdf_
SRDF Data and Writer.
planning_scene::PlanningScenePtr planning_scene_
Shared planning scene.
void removePoseByName(const std::string &pose_name, const std::string &group_name)
std::shared_ptr< urdf::Model > urdf_model_
planning_scene::PlanningScenePtr getPlanningScene()
Provide a shared planning scene.
std::filesystem::path srdf_pkg_relative_path_
Path relative to loaded configuration package.
std::string getChildOfJoint(const std::string &joint_name) const
Return the name of the child link of a joint.
moveit::core::RobotModelPtr getRobotModel() const
moveit::core::RobotModelPtr robot_model_
std::vector< std::string > getJointNames(const std::string &group_name, bool include_multi_dof=true, bool include_passive=true)
std::filesystem::path srdf_path_
Full file-system path to srdf.
void loadSRDFFile(const std::filesystem::path &package_path, const std::filesystem::path &relative_path)
Load SRDF File.
YAML::Node saveToYaml() const override
Optionally save "meta" information for saving in the .setup_assistant yaml file.
void onInit() override
Overridable initialization method.
std::vector< std::string > getLinkNames() const
void collectVariables(std::vector< TemplateVariable > &variables) override
Collect key/value pairs for use in templates.
void loadPrevious(const std::filesystem::path &package_path, const YAML::Node &node) override
Loads the configuration from an existing MoveIt configuration.
where all the data for each part of the configuration is stored.
rclcpp::Node::SharedPtr parent_node_
std::shared_ptr< DataWarehouse > config_data_
std::shared_ptr< rclcpp::Logger > logger_
static bool loadXmlFileToString(std::string &buffer, const std::string &path, const std::vector< std::string > &xacro_args)
helper that branches between loadFileToString() and loadXacroFileToString() based on result of isXacr...
bool getYamlProperty(const YAML::Node &node, const std::string &key, T &storage, const T &default_value=T())
bool acceleration_bounded_
Custom std::set comparator, used for sorting the joint_limits.yaml file into alphabetical order.
bool operator()(const moveit::core::JointModel *jm1, const moveit::core::JointModel *jm2) const
Simple Key/value pair for templates.