|
35 | 35 | #include <string> |
36 | 36 | #include <thread> |
37 | 37 |
|
| 38 | +#include <tinyxml2.h> |
38 | 39 | #include <hardware_interface/types/hardware_interface_type_values.hpp> |
39 | 40 | #include <pluginlib/class_list_macros.hpp> |
40 | 41 | #include <rclcpp/rclcpp.hpp> |
@@ -404,7 +405,6 @@ hardware_interface::CallbackReturn MujocoSystemInterface::on_init(const hardware |
404 | 405 | // Pull joint and sensor information |
405 | 406 | register_joints(info); |
406 | 407 | register_sensors(info); |
407 | | - set_initial_pose(); |
408 | 408 |
|
409 | 409 | // Construct and start the ROS node spinning |
410 | 410 | executor_ = std::make_unique<rclcpp::executors::MultiThreadedExecutor>(); |
@@ -833,6 +833,39 @@ void MujocoSystemInterface::register_joints(const hardware_interface::HardwareIn |
833 | 833 | { |
834 | 834 | joint_states_.resize(hardware_info.joints.size()); |
835 | 835 |
|
| 836 | + // Pull the name of the file to load for starting config, if present. We only override start position if that |
| 837 | + // parameter exists and it is not an empty string |
| 838 | + bool should_override_start_position = false; |
| 839 | + auto it = hardware_info.hardware_parameters.find("override_start_position_file"); |
| 840 | + if (it != hardware_info.hardware_parameters.end()) |
| 841 | + { |
| 842 | + should_override_start_position = !it->second.empty(); |
| 843 | + } |
| 844 | + |
| 845 | + // If we have that file present, load the initial positions from that file to the appropriate mj_data_ structures |
| 846 | + if (should_override_start_position) |
| 847 | + { |
| 848 | + std::string override_start_position_file = it->second; |
| 849 | + bool success = set_override_start_positions(override_start_position_file); |
| 850 | + if (!success) |
| 851 | + { |
| 852 | + RCLCPP_ERROR(rclcpp::get_logger("MujocoSystemInterface"), |
| 853 | + "Failed to load override start positions from %s. Falling back to urdf initial positions.", |
| 854 | + override_start_position_file.c_str()); |
| 855 | + should_override_start_position = false; |
| 856 | + } |
| 857 | + else |
| 858 | + { |
| 859 | + RCLCPP_INFO(rclcpp::get_logger("MujocoSystemInterface"), "Loaded initial positions from file %s.", |
| 860 | + override_start_position_file.c_str()); |
| 861 | + } |
| 862 | + } |
| 863 | + else |
| 864 | + { |
| 865 | + RCLCPP_INFO(rclcpp::get_logger("MujocoSystemInterface"), |
| 866 | + "override_start_position_file not passed. Loading initial positions from ros2_control xacro."); |
| 867 | + } |
| 868 | + |
836 | 869 | for (size_t joint_index = 0; joint_index < hardware_info.joints.size(); joint_index++) |
837 | 870 | { |
838 | 871 | auto joint = hardware_info.joints.at(joint_index); |
@@ -918,44 +951,56 @@ void MujocoSystemInterface::register_joints(const hardware_interface::HardwareIn |
918 | 951 | } |
919 | 952 | }; |
920 | 953 |
|
921 | | - // Set initial values if they are set in the info |
| 954 | + // Set initial values if they are set in the info, or from override start position file |
922 | 955 | for (const auto& state_if : joint.state_interfaces) |
923 | 956 | { |
924 | 957 | if (state_if.name == hardware_interface::HW_IF_POSITION) |
925 | 958 | { |
926 | | - last_joint_state.position = get_initial_value(state_if); |
| 959 | + last_joint_state.position = |
| 960 | + should_override_start_position ? mj_data_->qpos[joint_state.mj_pos_adr] : get_initial_value(state_if); |
927 | 961 | } |
928 | 962 | else if (state_if.name == hardware_interface::HW_IF_VELOCITY) |
929 | 963 | { |
930 | | - last_joint_state.velocity = get_initial_value(state_if); |
| 964 | + last_joint_state.velocity = |
| 965 | + should_override_start_position ? mj_data_->qvel[joint_state.mj_vel_adr] : get_initial_value(state_if); |
931 | 966 | } |
932 | 967 | else if (state_if.name == hardware_interface::HW_IF_EFFORT) |
933 | 968 | { |
| 969 | + // We never set data for effort from an initial conditions file, so just default to the initial value if it exists. |
934 | 970 | last_joint_state.effort = get_initial_value(state_if); |
935 | 971 | } |
936 | 972 | } |
937 | 973 |
|
938 | 974 | // command interfaces |
939 | | - // overwrite joint limit with min/max value |
940 | 975 | for (const auto& command_if : joint.command_interfaces) |
941 | 976 | { |
942 | 977 | // If available, always default to position control at the start |
943 | 978 | if (command_if.name.find(hardware_interface::HW_IF_POSITION) != std::string::npos) |
944 | 979 | { |
945 | 980 | last_joint_state.is_position_control_enabled = true; |
946 | | - last_joint_state.position_command = last_joint_state.position; |
| 981 | + last_joint_state.position_command = |
| 982 | + should_override_start_position ? mj_data_->ctrl[joint_state.mj_actuator_id] : last_joint_state.position; |
947 | 983 | } |
948 | 984 | else if (command_if.name.find(hardware_interface::HW_IF_VELOCITY) != std::string::npos) |
949 | 985 | { |
950 | 986 | last_joint_state.is_velocity_control_enabled = true; |
951 | | - last_joint_state.velocity_command = last_joint_state.velocity; |
| 987 | + last_joint_state.velocity_command = |
| 988 | + should_override_start_position ? mj_data_->ctrl[joint_state.mj_actuator_id] : last_joint_state.velocity; |
952 | 989 | } |
953 | 990 | else if (command_if.name.find(hardware_interface::HW_IF_EFFORT) != std::string::npos) |
954 | 991 | { |
955 | 992 | last_joint_state.is_effort_control_enabled = true; |
956 | | - last_joint_state.effort_command = last_joint_state.effort; |
| 993 | + last_joint_state.effort_command = |
| 994 | + should_override_start_position ? mj_data_->ctrl[joint_state.mj_actuator_id] : last_joint_state.effort; |
957 | 995 | } |
958 | 996 | } |
| 997 | + |
| 998 | + // When we override the start position, we set qpos from that file. Otherwise, we need to set it from initial |
| 999 | + // conditions from the urdf. |
| 1000 | + if (!should_override_start_position) |
| 1001 | + { |
| 1002 | + set_initial_pose(); |
| 1003 | + } |
959 | 1004 | } |
960 | 1005 | } |
961 | 1006 |
|
@@ -1054,6 +1099,77 @@ void MujocoSystemInterface::register_sensors(const hardware_interface::HardwareI |
1054 | 1099 | } |
1055 | 1100 | } |
1056 | 1101 |
|
| 1102 | +bool MujocoSystemInterface::set_override_start_positions(const std::string& override_start_position_file) |
| 1103 | +{ |
| 1104 | + tinyxml2::XMLDocument doc; |
| 1105 | + if (doc.LoadFile(override_start_position_file.c_str()) != tinyxml2::XML_SUCCESS) |
| 1106 | + { |
| 1107 | + RCLCPP_ERROR_STREAM(rclcpp::get_logger("MujocoSystemInterface"), |
| 1108 | + "Failed to load override start position file " << override_start_position_file.c_str() << "."); |
| 1109 | + return false; |
| 1110 | + } |
| 1111 | + |
| 1112 | + // get the <key> element |
| 1113 | + tinyxml2::XMLElement* keyElem = doc.FirstChildElement("key"); |
| 1114 | + if (!keyElem) |
| 1115 | + { |
| 1116 | + RCLCPP_ERROR_STREAM(rclcpp::get_logger("MujocoSystemInterface"), |
| 1117 | + "<key> element not found in override start position file."); |
| 1118 | + return false; |
| 1119 | + } |
| 1120 | + |
| 1121 | + auto parseAttr = [&](tinyxml2::XMLElement* elem, const char* attrName) -> std::vector<double> { |
| 1122 | + std::vector<double> result; |
| 1123 | + |
| 1124 | + const char* text = elem->Attribute(attrName); |
| 1125 | + if (!text) |
| 1126 | + { |
| 1127 | + RCLCPP_ERROR_STREAM(rclcpp::get_logger("MujocoSystemInterface"), |
| 1128 | + "Attribute '" << attrName << "' not found in override start position file."); |
| 1129 | + return result; // return empty vector |
| 1130 | + } |
| 1131 | + |
| 1132 | + std::stringstream ss(text); |
| 1133 | + double v; |
| 1134 | + while (ss >> v) |
| 1135 | + { |
| 1136 | + result.push_back(v); |
| 1137 | + } |
| 1138 | + |
| 1139 | + return result; |
| 1140 | + }; |
| 1141 | + |
| 1142 | + std::vector<double> qpos = parseAttr(keyElem, "qpos"); |
| 1143 | + std::vector<double> qvel = parseAttr(keyElem, "qvel"); |
| 1144 | + std::vector<double> ctrl = parseAttr(keyElem, "ctrl"); |
| 1145 | + |
| 1146 | + // we already put out an error message saying that it couldn't load specific things, so we don't need to say anything else |
| 1147 | + if (qpos.empty() || qvel.empty() || ctrl.empty()) |
| 1148 | + { |
| 1149 | + return false; |
| 1150 | + } |
| 1151 | + |
| 1152 | + if ((qpos.size() != static_cast<size_t>(mj_model_->nq)) || (qvel.size() != static_cast<size_t>(mj_model_->nv)) || |
| 1153 | + (ctrl.size() != static_cast<size_t>(mj_model_->nu))) |
| 1154 | + { |
| 1155 | + RCLCPP_ERROR_STREAM(rclcpp::get_logger("MujocoSystemInterface"), |
| 1156 | + "Mismatch in data types in override starting positions. Numbers are:\n\t" |
| 1157 | + << "qpos size in file: " << qpos.size() << ", qpos size in model: " << mj_model_->nq |
| 1158 | + << "\n\t" |
| 1159 | + << "qvel size in file: " << qvel.size() << ", qvel size in model: " << mj_model_->nv |
| 1160 | + << "\n\t" |
| 1161 | + << "ctrl size in file: " << ctrl.size() << ", ctrl size in model: " << mj_model_->nu); |
| 1162 | + return false; |
| 1163 | + } |
| 1164 | + |
| 1165 | + // copy data from the input information into the mj_data_ object |
| 1166 | + std::copy(qpos.begin(), qpos.end(), mj_data_->qpos); |
| 1167 | + std::copy(qvel.begin(), qvel.end(), mj_data_->qvel); |
| 1168 | + std::copy(ctrl.begin(), ctrl.end(), mj_data_->ctrl); |
| 1169 | + |
| 1170 | + return true; |
| 1171 | +} |
| 1172 | + |
1057 | 1173 | void MujocoSystemInterface::set_initial_pose() |
1058 | 1174 | { |
1059 | 1175 | for (auto& joint_state : joint_states_) |
|
0 commit comments