Skip to content

Commit 54e40c4

Browse files
authored
Merge pull request #34 from NASA-JSC-Robotics/override-start-position
Added capability to provide a key frame as starting configuration.
2 parents 5d38798 + f22a782 commit 54e40c4

File tree

5 files changed

+150
-8
lines changed

5 files changed

+150
-8
lines changed

README.md

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,15 @@ Just specify the plugin and point to a valid MJCF on launch:
5555
-->
5656
<param name="sim_speed_factor">5.0</param>
5757

58+
<!--
59+
Optional parameter to use the keyframe from a provided file as the starting configuration. This is mutually exclusive with
60+
the initial_value that can be used for state interfaces. This is intended to provide an alternative method to load an entire
61+
mujoco model state from a configuration that was saved by clicking 'Copy state' in the simulate window, and pasted into a
62+
config file. Expected use cases are to work on a specific part of an application that involves the environment being in a
63+
very specific starting configuration. If this parameter is an empty string, it will be ignored.
64+
-->
65+
<param name="override_start_position_file">$(find my_description)/config/start_positions.xml</param>
66+
5867
<!--
5968
Optional parameter to update the simulated camera's color and depth image publish rates. If no
6069
parameter is set then all cameras will publish at 5 hz. Note that all cameras in the sim currently

include/mujoco_ros2_simulation/mujoco_system_interface.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -135,6 +135,14 @@ class MujocoSystemInterface : public hardware_interface::SystemInterface
135135
*/
136136
void register_sensors(const hardware_interface::HardwareInfo& info);
137137

138+
/**
139+
* @brief Sets the initial simulation conditions (pos, vel, ctrl) values from provided filepath.
140+
*
141+
* @param override_start_position_file filepath that contains starting positions
142+
* @return success of reading the file and setting the positions
143+
*/
144+
bool set_override_start_positions(const std::string& override_start_position_file);
145+
138146
/**
139147
* @brief Set the initial pose for all actuators if provided in the URDF.
140148
*/

src/mujoco_system_interface.cpp

Lines changed: 124 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@
3535
#include <string>
3636
#include <thread>
3737

38+
#include <tinyxml2.h>
3839
#include <hardware_interface/types/hardware_interface_type_values.hpp>
3940
#include <pluginlib/class_list_macros.hpp>
4041
#include <rclcpp/rclcpp.hpp>
@@ -404,7 +405,6 @@ hardware_interface::CallbackReturn MujocoSystemInterface::on_init(const hardware
404405
// Pull joint and sensor information
405406
register_joints(info);
406407
register_sensors(info);
407-
set_initial_pose();
408408

409409
// Construct and start the ROS node spinning
410410
executor_ = std::make_unique<rclcpp::executors::MultiThreadedExecutor>();
@@ -833,6 +833,39 @@ void MujocoSystemInterface::register_joints(const hardware_interface::HardwareIn
833833
{
834834
joint_states_.resize(hardware_info.joints.size());
835835

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+
836869
for (size_t joint_index = 0; joint_index < hardware_info.joints.size(); joint_index++)
837870
{
838871
auto joint = hardware_info.joints.at(joint_index);
@@ -918,44 +951,56 @@ void MujocoSystemInterface::register_joints(const hardware_interface::HardwareIn
918951
}
919952
};
920953

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
922955
for (const auto& state_if : joint.state_interfaces)
923956
{
924957
if (state_if.name == hardware_interface::HW_IF_POSITION)
925958
{
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);
927961
}
928962
else if (state_if.name == hardware_interface::HW_IF_VELOCITY)
929963
{
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);
931966
}
932967
else if (state_if.name == hardware_interface::HW_IF_EFFORT)
933968
{
969+
// We never set data for effort from an initial conditions file, so just default to the initial value if it exists.
934970
last_joint_state.effort = get_initial_value(state_if);
935971
}
936972
}
937973

938974
// command interfaces
939-
// overwrite joint limit with min/max value
940975
for (const auto& command_if : joint.command_interfaces)
941976
{
942977
// If available, always default to position control at the start
943978
if (command_if.name.find(hardware_interface::HW_IF_POSITION) != std::string::npos)
944979
{
945980
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;
947983
}
948984
else if (command_if.name.find(hardware_interface::HW_IF_VELOCITY) != std::string::npos)
949985
{
950986
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;
952989
}
953990
else if (command_if.name.find(hardware_interface::HW_IF_EFFORT) != std::string::npos)
954991
{
955992
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;
957995
}
958996
}
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+
}
9591004
}
9601005
}
9611006

@@ -1054,6 +1099,77 @@ void MujocoSystemInterface::register_sensors(const hardware_interface::HardwareI
10541099
}
10551100
}
10561101

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+
10571173
void MujocoSystemInterface::set_initial_pose()
10581174
{
10591175
for (auto& joint_state : joint_states_)

test/config/start_positions.xml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
<key
2+
time="228.612"
3+
qpos="-0.249969 0.75"
4+
qvel="-3.9179e-06 1.06969e-09"
5+
ctrl="-0.25 0.75"
6+
/>

test/test_resources/test_robot.urdf

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -133,6 +133,9 @@
133133
<plugin>mujoco_ros2_simulation/MujocoSystemInterface</plugin>
134134
<param name="mujoco_model">$(find mujoco_ros2_simulation)/test_resources/scene.xml</param>
135135

136+
<!-- Uncomment this to use the keyframe from shown file as the starting configuration. -->
137+
<!-- <param name="override_start_position_file">$(find mujoco_ros2_simulation)/config/start_positions.xml</param> -->
138+
136139
<!-- Override the slowdown settings in the Simulate App and run at 3x speed -->
137140
<param name="sim_speed_factor">3.0</param>
138141

0 commit comments

Comments
 (0)