|
46 | 46 | #include <tesseract_srdf/srdf_model.h>
|
47 | 47 | #include <tesseract_srdf/utils.h>
|
48 | 48 |
|
| 49 | +#include <tesseract_scene_graph/graph.h> |
| 50 | +#include <tesseract_common/utils.h> |
| 51 | +#include <tesseract_common/yaml_utils.h> |
| 52 | + |
49 | 53 | %}
|
50 | 54 |
|
51 | 55 | // tesseract_srdf
|
|
55 | 59 | %include "tesseract_srdf/kinematics_information.h"
|
56 | 60 | %include "tesseract_srdf/srdf_model.h"
|
57 | 61 | %include "tesseract_srdf/utils.h"
|
| 62 | + |
| 63 | +%inline { |
| 64 | +tesseract_common::CalibrationInfo parseCalibrationConfigString(const tesseract_scene_graph::SceneGraph& scene_graph, |
| 65 | + const std::string& yaml_str) |
| 66 | +{ |
| 67 | + YAML::Node config; |
| 68 | + try |
| 69 | + { |
| 70 | + config = YAML::Load(yaml_str); |
| 71 | + } |
| 72 | + catch (...) |
| 73 | + { |
| 74 | + std::throw_with_nested(std::runtime_error("calibration_config: YAML failed to parse calibration config string")); |
| 75 | + } |
| 76 | + |
| 77 | + const YAML::Node& cal_info = config[tesseract_common::CalibrationInfo::CONFIG_KEY]; |
| 78 | + auto info = cal_info.as<tesseract_common::CalibrationInfo>(); |
| 79 | + |
| 80 | + // Check to make sure calibration joints exist |
| 81 | + for (const auto& cal_joint : info.joints) |
| 82 | + { |
| 83 | + if (scene_graph.getJoint(cal_joint.first) == nullptr) |
| 84 | + std::throw_with_nested(std::runtime_error("calibration_config: joint '" + cal_joint.first + "' does not exist!")); |
| 85 | + } |
| 86 | + |
| 87 | + return info; |
| 88 | +} |
| 89 | + |
| 90 | +tesseract_common::KinematicsPluginInfo parseKinematicsPluginConfigString(const std::string& yaml_str) |
| 91 | +{ |
| 92 | + |
| 93 | + YAML::Node config; |
| 94 | + try |
| 95 | + { |
| 96 | + config = YAML::Load(yaml_str); |
| 97 | + } |
| 98 | + catch (...) |
| 99 | + { |
| 100 | + std::throw_with_nested(std::runtime_error("kinematics_plugin_config: YAML failed to parse kinematics plugins string" )); |
| 101 | + } |
| 102 | + |
| 103 | + const YAML::Node& kin_plugin_info = config[tesseract_common::KinematicsPluginInfo::CONFIG_KEY]; |
| 104 | + |
| 105 | + return kin_plugin_info.as<tesseract_common::KinematicsPluginInfo>(); |
| 106 | +} |
| 107 | + |
| 108 | +tesseract_common::ContactManagersPluginInfo |
| 109 | +parseContactManagersPluginConfigString(const std::string& yaml_str) |
| 110 | +{ |
| 111 | + YAML::Node config; |
| 112 | + try |
| 113 | + { |
| 114 | + config = YAML::Load(yaml_str); |
| 115 | + } |
| 116 | + catch (...) |
| 117 | + { |
| 118 | + std::throw_with_nested(std::runtime_error("contact_managers_plugin_config: YAML failed to parse contact " |
| 119 | + "managers plugins string")); |
| 120 | + } |
| 121 | + |
| 122 | + const YAML::Node& cm_plugin_info = config[tesseract_common::ContactManagersPluginInfo::CONFIG_KEY]; |
| 123 | + return cm_plugin_info.as<tesseract_common::ContactManagersPluginInfo>(); |
| 124 | +} |
| 125 | +} |
0 commit comments