Skip to content

Commit

Permalink
refactor: apply clang-tidy patch
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidPL1 committed Nov 7, 2024
1 parent 2c7b392 commit 1eda184
Show file tree
Hide file tree
Showing 4 changed files with 11 additions and 11 deletions.
2 changes: 1 addition & 1 deletion mujoco_ros/include/mujoco_ros/viewer.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ class Viewer
// Clear the loading message
// Can be called instead of Load to clear the message without
// requesting the UI load a model
void LoadMessageClear(void);
void LoadMessageClear();

// Request that the simulation UI thread renders a new model optionally
void Load(mjModelPtr m, mjDataPtr d, const char *displayed_filename);
Expand Down
2 changes: 1 addition & 1 deletion mujoco_ros/src/viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2142,7 +2142,7 @@ void Viewer::LoadMessage(const char *displayed_filename)
}
}

void Viewer::LoadMessageClear(void)
void Viewer::LoadMessageClear()
{
{
MutexLock lock(mtx);
Expand Down
2 changes: 1 addition & 1 deletion mujoco_ros/test/mujoco_env_fixture.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class MujocoEnvTestWrapper : public MujocoEnv
int getNumCBReadyPlugins() { return cb_ready_plugins_.size(); }
void notifyGeomChange() { notifyGeomChanged(0); }

void load_filename(std::string filename)
void load_filename(const std::string &filename)
{
mju::strcpy_arr(queued_filename_, filename.c_str());
settings_.load_request = 2;
Expand Down
16 changes: 8 additions & 8 deletions mujoco_ros_laser/src/laser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ void readOptionalDoubleFromConfig(const XmlRpc::XmlRpcValue &config, const std::

LaserConfig::LaserConfig(const XmlRpc::XmlRpcValue &config, const std::string &frame_id, const std::string &name,
int site_attached)
: SensorConfig(std::move(frame_id)), name(name), site_attached(site_attached)
: SensorConfig(frame_id), name(name), site_attached(site_attached)
{
if (config.hasMember("visualize")) {
this->visualize = static_cast<bool>(config["visualize"]);
Expand Down Expand Up @@ -121,8 +121,8 @@ bool LaserPlugin::load(const mjModel *m, mjData *d)
if (rosparam_config_["sensors"].getType() == XmlRpc::XmlRpcValue::TypeArray) {
// iterate through configs
ROS_WARN_NAMED("lasers", "Is array");
for (int i = 0; i < rosparam_config_["sensors"].size(); ++i) {
initSensor(m, rosparam_config_["sensors"][i]);
for (auto &i : rosparam_config_["sensors"]) {
initSensor(m, i.second);
}
} else {
ROS_ERROR_NAMED("lasers", "Sensors config is not an array!");
Expand Down Expand Up @@ -223,7 +223,7 @@ void processRay(const mjModel *model, mjData *data, std::mt19937 rand_generator,
}
// add ray to start position
mju_addScl3(target, pos, target, dist);
mjv_initGeom(geom, mjGEOM_LINE, NULL, NULL, NULL, rgba);
mjv_initGeom(geom, mjGEOM_LINE, nullptr, nullptr, nullptr, rgba);
mjv_connector(geom, mjGEOM_LINE, 1., pos, target);
}

Expand All @@ -243,8 +243,8 @@ void LaserPlugin::computeLasers(const mjModel *model, mjData *data)
mjtNum rot[9];

mjtByte ignore_groups[mjNGROUP] = { 0 };
for (int i = 0; i < mjNGROUP; ++i) {
ignore_groups[i] = 1;
for (unsigned char &ignore_group : ignore_groups) {
ignore_group = 1;
}
ignore_groups[1] = 0; // ignore group 1 (robot geom)

Expand Down Expand Up @@ -290,8 +290,8 @@ void LaserPlugin::computeLasersMultithreaded(const mjModel *model, mjData *data)
mjtNum rot[9];

mjtByte ignore_groups[mjNGROUP] = { 0 };
for (int i = 0; i < mjNGROUP; ++i) {
ignore_groups[i] = 1;
for (unsigned char &ignore_group : ignore_groups) {
ignore_group = 1;
}
ignore_groups[1] = 0; // ignore group 1 (robot geom)

Expand Down

0 comments on commit 1eda184

Please sign in to comment.