Skip to content

Commit

Permalink
[core] Remove irrelevant telemetry prefix. Replace controller telemet…
Browse files Browse the repository at this point in the history
…ry prefix by 'controller'.
  • Loading branch information
Alexis Duburcq authored and duburcqa committed Apr 12, 2024
1 parent 48043c1 commit f1168c4
Show file tree
Hide file tree
Showing 21 changed files with 127 additions and 122 deletions.
1 change: 1 addition & 0 deletions core/examples/double_pendulum/double_pendulum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ int main(int /* argc */, char * /* argv */[])
const auto dataPath = jiminySrcPath / "data/toys_models";
const auto urdfPath = dataPath / "double_pendulum/double_pendulum.urdf";
const auto outputDirPath = std::filesystem::temp_directory_path();
std::cout << "Output directory: " << outputDirPath << std::endl;

// =====================================================================
// ============ Instantiate and configure the simulation ===============
Expand Down
1 change: 1 addition & 0 deletions core/examples/external_project/double_pendulum.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ int main(int argc, char * argv[])
const std::filesystem::path filePath(__FILE__);
const auto urdfPath = filePath.parent_path() / "double_pendulum.urdf";
const auto outputDirPath = std::filesystem::temp_directory_path();
std::cout << "Output directory: " << outputDirPath << std::endl;

// =====================================================================
// ============ Instantiate and configure the simulation ===============
Expand Down
2 changes: 1 addition & 1 deletion core/include/jiminy/core/control/abstract_controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
namespace jiminy
{
/// \brief Namespace of the telemetry object.
inline constexpr std::string_view CONTROLLER_TELEMETRY_NAMESPACE{"HighLevelController"};
inline constexpr std::string_view CONTROLLER_TELEMETRY_NAMESPACE{"controller"};

class TelemetrySender;
class TelemetryData;
Expand Down
2 changes: 1 addition & 1 deletion core/include/jiminy/core/engine/engine.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

namespace jiminy
{
inline constexpr std::string_view ENGINE_TELEMETRY_NAMESPACE{"HighLevelController"};
inline constexpr std::string_view ENGINE_TELEMETRY_NAMESPACE{""};

enum class ContactModelType : uint8_t
{
Expand Down
12 changes: 6 additions & 6 deletions core/include/jiminy/core/utilities/helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,14 +100,14 @@ namespace jiminy
bool JIMINY_DLLAPI endsWith(const std::string & str, const std::string & substr);

std::string JIMINY_DLLAPI addCircumfix(std::string fieldname, // Make a copy
const std::string_view & prefix = {},
const std::string_view & suffix = {},
const std::string_view & delimiter = {});
const std::string_view & prefix,
const std::string_view & suffix,
const std::string_view & delimiter);
std::vector<std::string> JIMINY_DLLAPI addCircumfix(
const std::vector<std::string> & fieldnames,
const std::string_view & prefix = {},
const std::string_view & suffix = {},
const std::string_view & delimiter = {});
const std::string_view & prefix,
const std::string_view & suffix,
const std::string_view & delimiter);

std::string JIMINY_DLLAPI removeSuffix(std::string fieldname, // Make a copy
const std::string & suffix);
Expand Down
19 changes: 11 additions & 8 deletions core/src/engine/engine.cc
Original file line number Diff line number Diff line change
Expand Up @@ -571,39 +571,42 @@ namespace jiminy
auto energyIt = energy_.begin();
for (; robotIt != robots_.end(); ++robotIt, ++robotDataIt, ++energyIt)
{
// Define proxy for convenience
const std::string & robotName = (*robotIt)->getName();

// Generate the log fieldnames
robotDataIt->logPositionFieldnames =
addCircumfix((*robotIt)->getLogPositionFieldnames(),
(*robotIt)->getName(),
robotName,
{},
TELEMETRY_FIELDNAME_DELIMITER);
robotDataIt->logVelocityFieldnames =
addCircumfix((*robotIt)->getLogVelocityFieldnames(),
(*robotIt)->getName(),
robotName,
{},
TELEMETRY_FIELDNAME_DELIMITER);
robotDataIt->logAccelerationFieldnames =
addCircumfix((*robotIt)->getLogAccelerationFieldnames(),
(*robotIt)->getName(),
robotName,
{},
TELEMETRY_FIELDNAME_DELIMITER);
robotDataIt->logForceExternalFieldnames =
addCircumfix((*robotIt)->getLogForceExternalFieldnames(),
(*robotIt)->getName(),
robotName,
{},
TELEMETRY_FIELDNAME_DELIMITER);
robotDataIt->logCommandFieldnames =
addCircumfix((*robotIt)->getLogCommandFieldnames(),
(*robotIt)->getName(),
robotName,
{},
TELEMETRY_FIELDNAME_DELIMITER);
robotDataIt->logMotorEffortFieldnames =
addCircumfix((*robotIt)->getLogMotorEffortFieldnames(),
(*robotIt)->getName(),
robotName,
{},
TELEMETRY_FIELDNAME_DELIMITER);
robotDataIt->logEnergyFieldname = addCircumfix(
"energy", (*robotIt)->getName(), {}, TELEMETRY_FIELDNAME_DELIMITER);
robotDataIt->logEnergyFieldname =
addCircumfix("energy", robotName, {}, TELEMETRY_FIELDNAME_DELIMITER);

// Register variables to the telemetry senders
if (engineOptions_->telemetry.enableConfiguration)
Expand Down
22 changes: 10 additions & 12 deletions core/src/robot/robot.cc
Original file line number Diff line number Diff line change
Expand Up @@ -525,22 +525,20 @@ namespace jiminy
// Generate the fieldnames associated with command
logCommandFieldnames_.clear();
logCommandFieldnames_.reserve(nmotors_);
std::transform(
motors_.begin(),
motors_.end(),
std::back_inserter(logCommandFieldnames_),
[](const auto & elem) -> std::string
{ return addCircumfix(elem->getName(), toString(JOINT_PREFIX_BASE, "Command")); });
std::transform(motors_.begin(),
motors_.end(),
std::back_inserter(logCommandFieldnames_),
[](const auto & elem) -> std::string
{ return toString(JOINT_PREFIX_BASE, "Command", elem->getName()); });

// Generate the fieldnames associated with motor efforts
logMotorEffortFieldnames_.clear();
logMotorEffortFieldnames_.reserve(nmotors_);
std::transform(
motors_.begin(),
motors_.end(),
std::back_inserter(logMotorEffortFieldnames_),
[](const auto & elem) -> std::string
{ return addCircumfix(elem->getName(), toString(JOINT_PREFIX_BASE, "Effort")); });
std::transform(motors_.begin(),
motors_.end(),
std::back_inserter(logMotorEffortFieldnames_),
[](const auto & elem) -> std::string
{ return toString(JOINT_PREFIX_BASE, "Effort", elem->getName()); });
}

void Robot::refreshSensorProxies()
Expand Down
4 changes: 2 additions & 2 deletions core/unit/engine_sanity_check.cc
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ TEST(EngineSanity, EnergyConservation)
std::shared_ptr<const LogData> logDataPtr = engine.getLog();
const Eigen::VectorXd timesCont = getLogVariable(*logDataPtr, "Global.Time");
ASSERT_DOUBLE_EQ(timesCont[timesCont.size() - 1], tf);
const Eigen::VectorXd energyCont = getLogVariable(*logDataPtr, "HighLevelController.energy");
const Eigen::VectorXd energyCont = getLogVariable(*logDataPtr, "energy");
ASSERT_GT(energyCont.size(), 0);

// Check that energy is constant
Expand Down Expand Up @@ -140,7 +140,7 @@ TEST(EngineSanity, EnergyConservation)
logDataPtr = engine.getLog();
const Eigen::VectorXd timesDisc = getLogVariable(*logDataPtr, "Global.Time");
ASSERT_DOUBLE_EQ(timesDisc[timesDisc.size() - 1], tf);
const Eigen::VectorXd energyDisc = getLogVariable(*logDataPtr, "HighLevelController.energy");
const Eigen::VectorXd energyDisc = getLogVariable(*logDataPtr, "energy");
ASSERT_GT(energyDisc.size(), 0);

// Check that energy is constant
Expand Down
4 changes: 2 additions & 2 deletions docs/spec/src/tlmc_format_specification.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ GROUP "/" {
(0): 1
}
}
DATASET "HighLevelController.controlOffsetTimestamp" {
DATASET "controlOffsetTimestamp" {
DATATYPE H5T_STRING {
STRSIZE 8;
STRPAD H5T_STR_NULLPAD;
Expand All @@ -73,7 +73,7 @@ GROUP "/" {
...
}
GROUP "variables" {
GROUP "HighLevelController.currentPositionLeftSagittalHip" {
GROUP "currentPositionLeftSagittalHip" {
DATASET "time" {
DATATYPE H5T_STD_I64LE
DATASPACE SIMPLE { ( 338623 ) / ( 338623 ) }
Expand Down
20 changes: 11 additions & 9 deletions python/gym_jiminy/common/gym_jiminy/common/envs/generic.py
Original file line number Diff line number Diff line change
Expand Up @@ -1031,7 +1031,7 @@ def plot(self,
"`plot` method.")

# Plot all registered variables
for key, fielnames in self.log_fieldnames.items():
for key, fieldnames in self.log_fieldnames.items():
# Filter state if requested
if not enable_block_states and key.endswith(".state"):
continue
Expand All @@ -1042,21 +1042,23 @@ def plot(self,
# scalar data over time to be displayed to the same subplot.
t = log_vars["Global.Time"]
tab_data: Dict[str, Union[np.ndarray, Dict[str, np.ndarray]]] = {}
if isinstance(fielnames, dict):
for group, fieldnames in fielnames.items():
if not isinstance(fieldnames, list):
if isinstance(fieldnames, dict):
for group, subfieldnames in fieldnames.items():
if not isinstance(subfieldnames, list):
LOGGER.error(
"Action space not supported by this method.")
return figure
value_map = extract_variables_from_log(
log_vars, subfieldnames, "controller", as_dict=True)
tab_data[group] = {
key.split(".", 2)[2]: value
for key, value in extract_variables_from_log(
log_vars, fieldnames, as_dict=True).items()}
elif isinstance(fielnames, list):
for key, value in value_map.items()}
elif isinstance(fieldnames, list):
value_map = extract_variables_from_log(
log_vars, fieldnames, "controller", as_dict=True)
tab_data.update({
key.split(".", 2)[2]: value
for key, value in extract_variables_from_log(
log_vars, fielnames, as_dict=True).items()})
for key, value in value_map.items()})

# Add action tab
figure.add_tab(key.replace(".", " "), t, tab_data)
Expand Down
4 changes: 2 additions & 2 deletions python/gym_jiminy/common/gym_jiminy/common/envs/locomotion.py
Original file line number Diff line number Diff line change
Expand Up @@ -424,8 +424,8 @@ def compute_reward(self,
# Y-axis. It is equal to 0.0 if the frontal displacement is
# perfectly symmetric wrt Y-axis over the whole trajectory.
if 'direction' in reward_mixture_keys:
frontal_displacement = abs(np.mean(self.log_data[
'HighLevelController.currentFreeflyerPositionTransY']))
frontal_displacement = abs(np.mean(
self.log_data['currentFreeflyerPositionTransY']))
reward_dict['direction'] = - frontal_displacement

# Compute the total reward
Expand Down
11 changes: 5 additions & 6 deletions python/gym_jiminy/unit_py/test_pipeline_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -92,16 +92,15 @@ def _test_pid_standing(self):
# Check that the joint velocity target is zero
time = log_vars["Global.Time"]
velocity_target = np.stack([
log_vars['.'.join((
'HighLevelController', self.env.controller.name, name))]
log_vars['.'.join(("controller", self.env.controller.name, name))]
for name in self.env.controller.fieldnames], axis=-1)
self.assertTrue(np.all(
np.abs(velocity_target[time > time[-1] - 1.0]) < 1.0e-9))

# Check that the whole-body robot velocity is close to zero at the end
velocity_mes = np.stack([
log_vars['.'.join(('HighLevelController', name))]
for name in self.env.robot.log_velocity_fieldnames], axis=-1)
log_vars[name] for name in self.env.robot.log_velocity_fieldnames
], axis=-1)
self.assertTrue(np.all(
np.abs(velocity_mes[time > time[-1] - 1.0]) < 1.0e-3))

Expand Down Expand Up @@ -202,9 +201,9 @@ def test_pid_controller(self):
ctrl_name = controller.name
n_motors = len(controller.fieldnames)
pos = env.log_data["variables"][".".join((
"HighLevelController", ctrl_name, "state", str(n_motors - 1)))]
"controller", ctrl_name, "state", str(n_motors - 1)))]
vel = env.log_data["variables"][".".join((
"HighLevelController", ctrl_name, controller.fieldnames[-1]))]
"controller", ctrl_name, controller.fieldnames[-1]))]

# Make sure that the position and velocity targets are consistent
np.testing.assert_allclose(
Expand Down
2 changes: 1 addition & 1 deletion python/gym_jiminy/unit_py/test_pipeline_design.py
Original file line number Diff line number Diff line change
Expand Up @@ -217,7 +217,7 @@ def configure_telemetry() -> InterfaceJiminyEnv:

# Check that the command is updated 1/2 low-level controller update
log_vars = env.log_data['variables']
u_log = log_vars['HighLevelController.currentCommandLF_HAA']
u_log = log_vars['currentCommandLF_HAA']
self.assertEqual(env.control_dt, 2 * env.unwrapped.control_dt)
self.assertTrue(np.all(u_log[:2] == 0.0))
self.assertNotEqual(u_log[1], u_log[2])
Expand Down
2 changes: 1 addition & 1 deletion python/jiminy_py/examples/double_pendulum.py
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ def internal_dynamics(self, t, q, v, u_custom):

# Plot some data using standard tools only
plt.figure()
plt.plot(log_vars['Global.Time'], log_vars['HighLevelController.energy'])
plt.plot(log_vars['Global.Time'], log_vars['energy'])
plt.title('Double pendulum energy')
plt.grid()
plt.show()
Expand Down
2 changes: 1 addition & 1 deletion python/jiminy_py/examples/tutorial.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@
"# Let's plot the joint position to see the pendulum fall.\n",
"import matplotlib.pyplot as plt\n",
"\n",
"plt.plot(log_vars['Global.Time'], log_vars['HighLevelController.currentPositionPendulum'])\n",
"plt.plot(log_vars['Global.Time'], log_vars['currentPositionPendulum'])\n",
"plt.title('Pendulum angle (rad)')\n",
"plt.grid()\n",
"plt.show()"
Expand Down
Loading

0 comments on commit f1168c4

Please sign in to comment.