Skip to content

Commit

Permalink
[core] Pass and return fundamental types by value instead of const re…
Browse files Browse the repository at this point in the history
…f. (#678)
  • Loading branch information
duburcqa committed Jan 2, 2024
1 parent bec047b commit 78515b2
Show file tree
Hide file tree
Showing 16 changed files with 118 additions and 116 deletions.
1 change: 0 additions & 1 deletion core/include/jiminy/core/engine/system.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ namespace jiminy
class AbstractController;
class LockGuardLocal;


// External force functors
using ForceProfileFunctor = std::function<pinocchio::Force(
float64_t /*t*/, const Eigen::VectorXd & /*q*/, const Eigen::VectorXd & /*v*/)>;
Expand Down
3 changes: 1 addition & 2 deletions core/include/jiminy/core/hardware/abstract_motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
namespace jiminy
{
class Robot;

class AbstractMotorBase;

/// \brief Structure holding the data for every motor.
Expand Down Expand Up @@ -123,7 +122,7 @@ namespace jiminy
const std::string & getName() const;

/// \brief Index of the motor.
const std::size_t & getIdx() const;
std::size_t getIdx() const;

/// \brief Name of the joint associated with the motor.
const std::string & getJointName() const;
Expand Down
5 changes: 2 additions & 3 deletions core/include/jiminy/core/hardware/abstract_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@ namespace jiminy
{
class TelemetryData;
class Robot;

class AbstractSensorBase;

// Sensor data holder
Expand Down Expand Up @@ -286,7 +285,7 @@ namespace jiminy
const std::string & getName() const;

/// \brief Index of the sensor of the global shared buffer.
virtual const std::size_t & getIdx() const = 0;
virtual std::size_t getIdx() const = 0;

/// \brief Type of the sensor.
virtual const std::string & getType() const = 0;
Expand Down Expand Up @@ -420,7 +419,7 @@ namespace jiminy
void updateTelemetryAll() override final;

virtual hresult_t setOptionsAll(const GenericConfig & sensorOptions) override final;
virtual const std::size_t & getIdx() const override final;
virtual std::size_t getIdx() const override final;
virtual const std::string & getType() const override final;
virtual const std::vector<std::string> & getFieldnames() const final;
virtual uint64_t getSize() const override final;
Expand Down
2 changes: 1 addition & 1 deletion core/include/jiminy/core/hardware/abstract_sensor.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ namespace jiminy
}

template<typename T>
const std::size_t & AbstractSensorTpl<T>::getIdx() const
std::size_t AbstractSensorTpl<T>::getIdx() const
{
return sensorIdx_;
}
Expand Down
2 changes: 1 addition & 1 deletion core/include/jiminy/core/hardware/basic_sensors.h
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ namespace jiminy
virtual hresult_t refreshProxies() final override;

const std::string & getMotorName() const;
const std::size_t & getMotorIdx() const;
std::size_t getMotorIdx() const;

private:
virtual hresult_t set(float64_t t,
Expand Down
2 changes: 1 addition & 1 deletion core/src/constraints/frame_constraint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ namespace jiminy
// Extract masked jacobian and drift, only containing fixed dofs
for (uint32_t i = 0; i < dofsFixed_.size(); ++i)
{
uint32_t dofIndex = dofsFixed_[i];
const uint32_t dofIndex = dofsFixed_[i];
jacobian_.row(i) = frameJacobian_.row(dofIndex);
drift_[i] = frameDrift_.toVector()[dofIndex];
}
Expand Down
126 changes: 65 additions & 61 deletions core/src/engine/engine_multi_robot.cc

Large diffs are not rendered by default.

11 changes: 6 additions & 5 deletions core/src/hardware/abstract_motor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -160,23 +160,24 @@ namespace jiminy
if (isInitialized_)
{
// Check if armature has changed
bool_t enableArmature = boost::get<bool_t>(motorOptions.at("enableArmature"));
const bool_t enableArmature = boost::get<bool_t>(motorOptions.at("enableArmature"));
internalBuffersMustBeUpdated |= (baseMotorOptions_->enableArmature != enableArmature);
if (enableArmature)
{
float64_t armature = boost::get<float64_t>(motorOptions.at("armature"));
const float64_t armature = boost::get<float64_t>(motorOptions.at("armature"));
internalBuffersMustBeUpdated |= //
std::abs(armature - baseMotorOptions_->armature) > EPS;
}

// Check if command limit has changed
bool_t commandLimitFromUrdf =
const bool_t commandLimitFromUrdf =
boost::get<bool_t>(motorOptions.at("commandLimitFromUrdf"));
internalBuffersMustBeUpdated |=
(baseMotorOptions_->commandLimitFromUrdf != commandLimitFromUrdf);
if (!commandLimitFromUrdf)
{
float64_t commandLimit = boost::get<float64_t>(motorOptions.at("commandLimit"));
const float64_t commandLimit =
boost::get<float64_t>(motorOptions.at("commandLimit"));
internalBuffersMustBeUpdated |=
std::abs(commandLimit - baseMotorOptions_->commandLimit) > EPS;
}
Expand Down Expand Up @@ -353,7 +354,7 @@ namespace jiminy
return name_;
}

const std::size_t & AbstractMotorBase::getIdx() const
std::size_t AbstractMotorBase::getIdx() const
{
return motorIdx_;
}
Expand Down
15 changes: 7 additions & 8 deletions core/src/hardware/basic_motors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -104,18 +104,17 @@ namespace jiminy
It is computed on joint side instead of the motor. */
if (motorOptions_->enableFriction)
{
float64_t vJoint = v;
if (vJoint > 0)
if (v > 0)
{
data() += motorOptions_->frictionViscousPositive * vJoint +
motorOptions_->frictionDryPositive *
tanh(motorOptions_->frictionDrySlope * vJoint);
data() +=
motorOptions_->frictionViscousPositive * v +
motorOptions_->frictionDryPositive * tanh(motorOptions_->frictionDrySlope * v);
}
else
{
data() += motorOptions_->frictionViscousNegative * vJoint +
motorOptions_->frictionDryNegative *
tanh(motorOptions_->frictionDrySlope * vJoint);
data() +=
motorOptions_->frictionViscousNegative * v +
motorOptions_->frictionDryNegative * tanh(motorOptions_->frictionDrySlope * v);
}
}

Expand Down
12 changes: 6 additions & 6 deletions core/src/hardware/basic_sensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -386,7 +386,7 @@ namespace jiminy
GET_ROBOT_IF_INITIALIZED()

// Get the sum of external forces applied on parent joint
pinocchio::JointIndex i = parentJointIdx_;
const pinocchio::JointIndex i = parentJointIdx_;
const pinocchio::Force & fJoint = fExternal[i];

// Transform the force from joint frame to sensor frame
Expand Down Expand Up @@ -489,12 +489,12 @@ namespace jiminy
GET_ROBOT_IF_INITIALIZED()

const auto & joint = robot->pncModel_.joints[jointIdx_];
int32_t jointPositionIdx = joint.idx_q();
int32_t jointVelocityIdx = joint.idx_v();
const int32_t jointPositionIdx = joint.idx_q();
const int32_t jointVelocityIdx = joint.idx_v();
if (jointType_ == JointModelType::ROTARY_UNBOUNDED)
{
float64_t cosTheta = q[jointPositionIdx];
float64_t sinTheta = q[jointPositionIdx + 1];
const float64_t cosTheta = q[jointPositionIdx];
const float64_t sinTheta = q[jointPositionIdx + 1];
data()[0] = std::atan2(sinTheta, cosTheta);
}
else
Expand Down Expand Up @@ -564,7 +564,7 @@ namespace jiminy
return motorName_;
}

const std::size_t & EffortSensor::getMotorIdx() const
std::size_t EffortSensor::getMotorIdx() const
{
return motorIdx_;
}
Expand Down
13 changes: 7 additions & 6 deletions core/src/robot/model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1159,10 +1159,11 @@ namespace jiminy

for (const std::string & jointName : rigidJointsNames_)
{
pinocchio::JointIndex jointIdx = pncModel_.getJointId(jointName);
const pinocchio::JointIndex jointIdx = pncModel_.getJointId(jointName);

// Add bias to com position
float64_t comBiasStd = mdlOptions_->dynamics.centerOfMassPositionBodiesBiasStd;
const float64_t comBiasStd =
mdlOptions_->dynamics.centerOfMassPositionBodiesBiasStd;
if (comBiasStd > EPS)
{
Eigen::Vector3d & comRelativePositionBody =
Expand All @@ -1173,7 +1174,7 @@ namespace jiminy

/* Add bias to body mass.
It cannot be less than min(original mass, 1g) for numerical stability. */
float64_t massBiasStd = mdlOptions_->dynamics.massBodiesBiasStd;
const float64_t massBiasStd = mdlOptions_->dynamics.massBodiesBiasStd;
if (massBiasStd > EPS)
{
float64_t & massBody = pncModel_.inertias[jointIdx].mass();
Expand All @@ -1188,7 +1189,7 @@ namespace jiminy
small rotation is applied to the principal axes based on a randomly generated
rotation axis. Finally, the biased inertia matrix is obtained doing
`A @ diag(M) @ A.T`. If no bias, the original inertia matrix is recovered. */
float64_t inertiaBiasStd = mdlOptions_->dynamics.inertiaBodiesBiasStd;
const float64_t inertiaBiasStd = mdlOptions_->dynamics.inertiaBodiesBiasStd;
if (inertiaBiasStd > EPS)
{
pinocchio::Symmetric3 & inertiaBody = pncModel_.inertias[jointIdx].inertia();
Expand All @@ -1207,7 +1208,7 @@ namespace jiminy
}

// Add bias to relative body position (rotation excluded !)
float64_t relativeBodyPosBiasStd =
const float64_t relativeBodyPosBiasStd =
mdlOptions_->dynamics.relativePositionBodiesBiasStd;
if (relativeBodyPosBiasStd > EPS)
{
Expand Down Expand Up @@ -1813,7 +1814,7 @@ namespace jiminy
"centerOfMassPositionBodiesBiasStd",
"relativePositionBodiesBiasStd"}})
{
float64_t value = boost::get<float64_t>(dynOptionsHolder.at(field));
const float64_t value = boost::get<float64_t>(dynOptionsHolder.at(field));
if (0.9 < value || value < 0.0)
{
PRINT_ERROR(
Expand Down
10 changes: 5 additions & 5 deletions core/src/solver/constraint_solvers.cc
Original file line number Diff line number Diff line change
Expand Up @@ -144,10 +144,10 @@ namespace jiminy
const ConstraintBlock & block = constraintData.blocks[i];
const Eigen::Index * fIdx = block.fIdx;
const std::uint_fast8_t & fSize = block.fSize;
Eigen::Index o = constraintData.startIdx;
const Eigen::Index o = constraintData.startIdx;
const Eigen::Index i0 = o + fIdx[0];
float64_t hi = block.hi;
float64_t lo = block.lo;
const float64_t hi = block.hi;
const float64_t lo = block.lo;
float64_t & e = x[i0];

// Bypass zero-ed coefficients
Expand All @@ -169,7 +169,7 @@ namespace jiminy
{
const Eigen::Index k = o + fIdx[j];
y_[k] = b[k] - A.col(k).dot(x);
float64_t A_kk = A(k, k);
const float64_t A_kk = A(k, k);
if (A_kk > A_max)
{
A_max = A_kk;
Expand Down Expand Up @@ -202,7 +202,7 @@ namespace jiminy
float64_t squaredNorm = e * e;
for (std::uint_fast8_t j = 1; j < fSize - 1; ++j)
{
float64_t f = xConst[fIdx[j]];
const float64_t f = xConst[fIdx[j]];
squaredNorm += f * f;
}
if (squaredNorm > thr * thr)
Expand Down
2 changes: 1 addition & 1 deletion core/src/utilities/json.cc
Original file line number Diff line number Diff line change
Expand Up @@ -263,7 +263,7 @@ namespace jiminy
}
else
{
field = Eigen::VectorXd();
field = Eigen::VectorXd{};
}
}
else
Expand Down
22 changes: 11 additions & 11 deletions core/src/utilities/pinocchio.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ namespace jiminy
++i)
{
// Get joint starting and ending index in position vector.
int32_t startIdx = model.joints[i].idx_q();
const int32_t startIdx = model.joints[i].idx_q();
const int32_t endIdx = startIdx + model.joints[i].nq();

// If idx is between start and end, we found the joint we were looking for.
Expand All @@ -55,7 +55,7 @@ namespace jiminy
++i)
{
// Get joint starting and ending index in velocity vector.
int32_t startIdx = model.joints[i].idx_v();
const int32_t startIdx = model.joints[i].idx_v();
const int32_t endIdx = startIdx + model.joints[i].nv();

// If idx is between start and end, we found the joint we were looking for
Expand Down Expand Up @@ -303,9 +303,9 @@ namespace jiminy
return hresult_t::ERROR_BAD_INPUT;
}

pinocchio::JointIndex jointModelIdx = model.getJointId(jointName);
int32_t jointPositionFirstIdx = model.joints[jointModelIdx].idx_q();
int32_t jointNq = model.joints[jointModelIdx].nq();
const pinocchio::JointIndex jointModelIdx = model.getJointId(jointName);
const int32_t jointPositionFirstIdx = model.joints[jointModelIdx].idx_q();
const int32_t jointNq = model.joints[jointModelIdx].nq();
jointPositionIdx.resize(static_cast<std::size_t>(jointNq));
std::iota(jointPositionIdx.begin(), jointPositionIdx.end(), jointPositionFirstIdx);

Expand Down Expand Up @@ -425,9 +425,9 @@ namespace jiminy
return hresult_t::ERROR_BAD_INPUT;
}

pinocchio::JointIndex jointModelIdx = model.getJointId(jointName);
int32_t jointVelocityFirstIdx = model.joints[jointModelIdx].idx_v();
int32_t jointNv = model.joints[jointModelIdx].nv();
const pinocchio::JointIndex jointModelIdx = model.getJointId(jointName);
const int32_t jointVelocityFirstIdx = model.joints[jointModelIdx].idx_v();
const int32_t jointNv = model.joints[jointModelIdx].nv();
jointVelocityIdx.resize(static_cast<std::size_t>(jointNv));
std::iota(jointVelocityIdx.begin(), jointVelocityIdx.end(), jointVelocityFirstIdx);

Expand All @@ -446,7 +446,7 @@ namespace jiminy
return hresult_t::ERROR_BAD_INPUT;
}

pinocchio::JointIndex jointModelIdx = model.getJointId(jointName);
const pinocchio::JointIndex jointModelIdx = model.getJointId(jointName);
jointVelocityFirstIdx = model.joints[jointModelIdx].idx_v();

return hresult_t::SUCCESS;
Expand Down Expand Up @@ -694,7 +694,7 @@ namespace jiminy
// Add new joint to frame list
pinocchio::FrameIndex childFrameIdx;
getFrameIdx(modelInOut, childJointNameIn, childFrameIdx); // Cannot fail at this point
pinocchio::FrameIndex newFrameIdx = modelInOut.addJointFrame(
const pinocchio::FrameIndex newFrameIdx = modelInOut.addJointFrame(
newJointIdx, static_cast<int32_t>(modelInOut.frames[childFrameIdx].previousFrame));

// Update child joint previousFrame index
Expand Down Expand Up @@ -827,7 +827,7 @@ namespace jiminy
{
continue;
}
pinocchio::JointIndex childJointIdx = modelInOut.frames[childFrameIdx].parent;
const pinocchio::JointIndex childJointIdx = modelInOut.frames[childFrameIdx].parent;

// Set child joint to be a child of the new joint
modelInOut.parents[childJointIdx] = newJointIdx;
Expand Down
4 changes: 2 additions & 2 deletions python/jiminy_pywrap/include/jiminy/python/utilities.h
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ namespace jiminy::python
{
if (strncmp(s.basename, "void", 4) == 0)
{
static const char * none = "None";
static char constexpr none[] = "None";
return none;
}
const PyTypeObject * py_type = s.pytype_f ? s.pytype_f() : nullptr;
Expand All @@ -132,7 +132,7 @@ namespace jiminy::python
}
else
{
static const char * object = "object";
static char constexpr object[] = "object";
return object;
}
}
Expand Down
4 changes: 2 additions & 2 deletions python/jiminy_pywrap/src/sensors.cc
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ namespace jiminy::python
for (const auto & sensorData : sensorsDataType.second)
{
const std::string & sensorName = sensorData.name;
const std::size_t & sensorIdx = sensorData.idx;
std::size_t sensorIdx = sensorData.idx;
const Eigen::Ref<const Eigen::VectorXd> & sensorDataValue = sensorData.value;
s << " (" << sensorIdx << ") " << sensorName << ": "
<< sensorDataValue.transpose().format(HeavyFmt);
Expand Down Expand Up @@ -275,7 +275,7 @@ namespace jiminy::python
for (std::size_t i = 0; i < fieldnames.size(); ++i)
{
const std::string & field = fieldnames[i];
float64_t value = sensorDataValue[i];
const float64_t value = sensorDataValue[i];
if (i > 0)
{
s << ", ";
Expand Down

0 comments on commit 78515b2

Please sign in to comment.