Skip to content

Commit

Permalink
[pre-commit.ci] auto fixes from pre-commit.com hooks
Browse files Browse the repository at this point in the history
for more information, see https://pre-commit.ci
  • Loading branch information
pre-commit-ci[bot] committed Mar 12, 2024
1 parent 1fc6dab commit 29400e0
Show file tree
Hide file tree
Showing 51 changed files with 236 additions and 325 deletions.
2 changes: 1 addition & 1 deletion include/mc_control/ControllerClient.h
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ struct MC_CONTROL_CLIENT_DLLAPI ControllerClient
virtual void stopped() {}

/** Should be implemented to create a new category container */
virtual void category(const std::vector<std::string> & parent, const std::string & category){};
virtual void category(const std::vector<std::string> & parent, const std::string & category) {};

/** Should be implemented to create a label for data that can be displayed as string */
inline virtual void label(const ElementId & id, const std::string &) { default_impl("Label", id); }
Expand Down
5 changes: 2 additions & 3 deletions include/mc_rbdyn/gui/RobotSurface.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,8 @@
namespace mc_rbdyn::gui
{

static const mc_rtc::gui::LineConfig defaultSurfaceConfig = []() {
return mc_rtc::gui::LineConfig{mc_rtc::gui::Color::Green, 0.01};
}();
static const mc_rtc::gui::LineConfig defaultSurfaceConfig = []()
{ return mc_rtc::gui::LineConfig{mc_rtc::gui::Color::Green, 0.01}; }();

/** Helper function to create a GUI element from a surface object inside a robot
*
Expand Down
14 changes: 4 additions & 10 deletions include/mc_rtc/gui/plot/AbscissaOrdinate.h
Original file line number Diff line number Diff line change
Expand Up @@ -129,21 +129,15 @@ auto XY(std::string_view name,
if constexpr(std::is_same_v<std::decay_t<MaybeGetColor>, Color>)
{
return impl::AbscissaOrdinate(
name,
[get_x_fn, get_y_fn](XYCacheT & cache) {
cache.push_back({get_x_fn(), get_y_fn()});
},
color, style, side);
name, [get_x_fn, get_y_fn](XYCacheT & cache) { cache.push_back({get_x_fn(), get_y_fn()}); }, color, style,
side);
}
else
{
static_assert(details::CheckReturnType<MaybeGetColor, Color>::value, "XY color callback should return a color");
return impl::AbscissaOrdinateWithColor(
name,
[get_x_fn, get_y_fn](XYCacheT & cache) {
cache.push_back({get_x_fn(), get_y_fn()});
},
color, style, side);
name, [get_x_fn, get_y_fn](XYCacheT & cache) { cache.push_back({get_x_fn(), get_y_fn()}); }, color, style,
side);
}
}

Expand Down
11 changes: 4 additions & 7 deletions include/mc_rtc/log/Logger.h
Original file line number Diff line number Diff line change
Expand Up @@ -221,9 +221,8 @@ struct MC_RTC_UTILS_DLLAPI Logger
}
auto log_type = log::callback_is_serializable<CallbackT>::log_type;
log_events_.push_back(KeyAddedEvent{log_type, name});
log_entries_.push_back({log_type, name, source, [get_fn](mc_rtc::MessagePackBuilder & builder) mutable {
mc_rtc::log::LogWriter<base_t>::write(get_fn(), builder);
}});
log_entries_.push_back({log_type, name, source, [get_fn](mc_rtc::MessagePackBuilder & builder) mutable
{ mc_rtc::log::LogWriter<base_t>::write(get_fn(), builder); }});
}

/** Add a log entry from a source and a compile-time pointer to member
Expand All @@ -248,8 +247,7 @@ struct MC_RTC_UTILS_DLLAPI Logger
void addLogEntry(const std::string & name, const SourceT * source, bool overwrite = false)
{
using MemberT = decltype(source->*member);
addLogEntry(
name, source, [source]() -> const MemberT & { return source->*member; }, overwrite);
addLogEntry(name, source, [source]() -> const MemberT & { return source->*member; }, overwrite);
}

/** Add a log entry from a source and a compile-time pointer to method
Expand All @@ -274,8 +272,7 @@ struct MC_RTC_UTILS_DLLAPI Logger
void addLogEntry(const std::string & name, const SourceT * source, bool overwrite = false)
{
using MethodRetT = decltype((source->*method)());
addLogEntry(
name, source, [source]() -> MethodRetT { return (source->*method)(); }, overwrite);
addLogEntry(name, source, [source]() -> MethodRetT { return (source->*method)(); }, overwrite);
}

/** Add a log entry into the log with no source
Expand Down
5 changes: 2 additions & 3 deletions include/mc_rtc/log/iterate_binary_log.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,9 +81,8 @@ inline bool iterate_binary_log(const std::string & fpath,
const std::string & time = "t")
{
return iterate_binary_log(
fpath,
[&callback](IterateBinaryLogData data) { return callback(data.keys, data.records, data.time.value_or(-1)); },
extract, time);
fpath, [&callback](IterateBinaryLogData data)
{ return callback(data.keys, data.records, data.time.value_or(-1)); }, extract, time);
}

} // namespace mc_rtc::log
4 changes: 2 additions & 2 deletions include/mc_tasks/SplineTrajectoryTask.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -383,8 +383,8 @@ void SplineTrajectoryTask<Derived>::addToGUI(mc_rtc::gui::StateBuilder & gui)
{
TrajectoryTask::addToGUI(gui);

gui.addElement({"Tasks", name_}, mc_rtc::gui::Checkbox(
"Paused", [this]() { return paused_; }, [this]() { paused_ = !paused_; }));
gui.addElement({"Tasks", name_},
mc_rtc::gui::Checkbox("Paused", [this]() { return paused_; }, [this]() { paused_ = !paused_; }));
gui.addElement({"Tasks", name_}, mc_rtc::gui::Transform("Surface pose", [this]() { return frame_->position(); }));

gui.addElement({"Tasks", name_}, mc_rtc::gui::Rotation(
Expand Down
2 changes: 1 addition & 1 deletion plugins/ROS/src/mc_tasks_ros/LookAtTFTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,4 +103,4 @@ static auto registered = mc_tasks::MetaTaskLoader::register_load_function(
t->load(solver, config);
return t;
});
}
} // namespace
32 changes: 11 additions & 21 deletions src/mc_control/MCController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -415,9 +415,8 @@ void MCController::addRobotToGUI(const mc_rbdyn::Robot & r)
data("joints").add(r.name(), r.module().ref_joint_order());
data("frames").add(r.name(), r.frames());
auto name = r.name();
gui()->addElement(
{"Robots"},
mc_rtc::gui::Robot(r.name(), [name, this]() -> const mc_rbdyn::Robot & { return this->outputRobot(name); }));
gui()->addElement({"Robots"}, mc_rtc::gui::Robot(r.name(), [name, this]() -> const mc_rbdyn::Robot &
{ return this->outputRobot(name); }));
}

void MCController::addRobotToLog(const mc_rbdyn::Robot & r)
Expand Down Expand Up @@ -493,40 +492,32 @@ void MCController::addRobotToLog(const mc_rbdyn::Robot & r)
{
logger().addLogEntry(entry("ff"),
[this, name]() -> const sva::PTransformd & { return outputRobot(name).mbc().bodyPosW[0]; });
logger().addLogEntry(entry("ff_real"),
[this, name]() -> const sva::PTransformd &
logger().addLogEntry(entry("ff_real"), [this, name]() -> const sva::PTransformd &
{ return outputRealRobot(name).mbc().bodyPosW[0]; });
}
// Log all force sensors
for(const auto & fs : robot(name).forceSensors())
{
const auto & fs_name = fs.name();
logger().addLogEntry(entry_str(fs.name()),
[this, name, fs_name]() -> const sva::ForceVecd &
logger().addLogEntry(entry_str(fs.name()), [this, name, fs_name]() -> const sva::ForceVecd &
{ return robot(name).forceSensor(fs_name).wrench(); });
}
// Log all body sensors
const auto & bodySensors = robot(name).bodySensors();
for(size_t i = 0; i < bodySensors.size(); ++i)
{
const auto & bs_name = bodySensors[i].name();
logger().addLogEntry(entry_str(bs_name + "_position"),
[this, name, bs_name]() -> const Eigen::Vector3d &
logger().addLogEntry(entry_str(bs_name + "_position"), [this, name, bs_name]() -> const Eigen::Vector3d &
{ return robot(name).bodySensor(bs_name).position(); });
logger().addLogEntry(entry_str(bs_name + "_orientation"),
[this, name, bs_name]() -> const Eigen::Quaterniond &
logger().addLogEntry(entry_str(bs_name + "_orientation"), [this, name, bs_name]() -> const Eigen::Quaterniond &
{ return robot(name).bodySensor(bs_name).orientation(); });
logger().addLogEntry(entry_str(bs_name + "_linearVelocity"),
[this, name, bs_name]() -> const Eigen::Vector3d &
logger().addLogEntry(entry_str(bs_name + "_linearVelocity"), [this, name, bs_name]() -> const Eigen::Vector3d &
{ return robot(name).bodySensor(bs_name).linearVelocity(); });
logger().addLogEntry(entry_str(bs_name + "_angularVelocity"),
[this, name, bs_name]() -> const Eigen::Vector3d &
logger().addLogEntry(entry_str(bs_name + "_angularVelocity"), [this, name, bs_name]() -> const Eigen::Vector3d &
{ return robot(name).bodySensor(bs_name).angularVelocity(); });
logger().addLogEntry(entry_str(bs_name + "_linearAcceleration"),
[this, name, bs_name]() -> const Eigen::Vector3d &
logger().addLogEntry(entry_str(bs_name + "_linearAcceleration"), [this, name, bs_name]() -> const Eigen::Vector3d &
{ return robot(name).bodySensor(bs_name).linearAcceleration(); });
logger().addLogEntry(entry_str(bs_name + "_angularAcceleration"),
[this, name, bs_name]() -> const Eigen::Vector3d &
logger().addLogEntry(entry_str(bs_name + "_angularAcceleration"), [this, name, bs_name]() -> const Eigen::Vector3d &
{ return robot(name).bodySensor(bs_name).angularAcceleration(); });
}
// Log all joint sensors
Expand Down Expand Up @@ -766,8 +757,7 @@ void MCController::reset(const ControllerResetData & reset_data)
mc_rtc::gui::FormNumberInput("Friction", false, mc_rbdyn::Contact::defaultFriction),
mc_rtc::gui::FormArrayInput<Eigen::Vector6d>("dof", false, Eigen::Vector6d::Ones())));
}
logger().addLogEntry(
"perf_UpdateContacts", [this]() { return updateContacts_dt_.count(); }, true);
logger().addLogEntry("perf_UpdateContacts", [this]() { return updateContacts_dt_.count(); }, true);
}

void MCController::updateContacts()
Expand Down
3 changes: 1 addition & 2 deletions src/mc_control/fsm/Executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,7 @@ void Executor::init(Controller & ctl,
else { log_entry += "_Main"; }
ctl.logger().addLogEntry(log_entry, this, [this]() { return curr_state_; });
log_entry = "perf_" + log_entry;
ctl.logger().addLogEntry(log_entry, this,
[this]()
ctl.logger().addLogEntry(log_entry, this, [this]()
{ return state_create_dt_.count() + state_run_dt_.count() + state_teardown_dt_.count(); });
ctl.logger().addLogEntry(log_entry + "_create", this, [this]() { return state_create_dt_.count(); });
ctl.logger().addLogEntry(log_entry + "_run", this, [this]() { return state_run_dt_.count(); });
Expand Down
4 changes: 1 addition & 3 deletions src/mc_control/fsm/states/Message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,7 @@ void MessageState::start(Controller & ctl)
else if(logType_ == "success") { mc_rtc::log::success(message); }
else if(logType_ == "warning") { mc_rtc::log::warning(message); }
else if(logType_ == "error") { mc_rtc::log::error(message); }
else if(logType_ == "none")
{ /* Do not log anything to the terminal */
}
else if(logType_ == "none") { /* Do not log anything to the terminal */ }
else
{
mc_rtc::log::error("{} Provided log type {} is invalid, assuming info. Supported types are [info, success, "
Expand Down
9 changes: 4 additions & 5 deletions src/mc_control/mc_global_controller_gui.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,10 @@ void MCGlobalController::initGUI()
targetCat.push_back("Targets");
for(const auto & joint : g_ptr->activeJoints())
{
gui->addElement(targetCat,
mc_rtc::gui::NumberSlider(
joint, [joint, g_ptr]() { return g_ptr->curOpening(joint); },
[joint, g_ptr](double targetOpening) { g_ptr->setTargetOpening(joint, targetOpening); },
0, 1));
gui->addElement(targetCat, mc_rtc::gui::NumberSlider(
joint, [joint, g_ptr]() { return g_ptr->curOpening(joint); },
[joint, g_ptr](double targetOpening)
{ g_ptr->setTargetOpening(joint, targetOpening); }, 0, 1));
}

category.push_back("Safety");
Expand Down
3 changes: 1 addition & 2 deletions src/mc_observers/EncoderObserver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,8 +173,7 @@ void EncoderObserver::addToLogger(const mc_control::MCController & ctl,
}
else if(velUpdate_ == VelUpdate::EncoderVelocities)
{
logger.addLogEntry(category + "_encoderVelocities", this,
[this, &ctl]() -> const std::vector<double> &
logger.addLogEntry(category + "_encoderVelocities", this, [this, &ctl]() -> const std::vector<double> &
{ return ctl.robot(robot_).encoderVelocities(); });
}
else if(velUpdate_ == VelUpdate::Control)
Expand Down
7 changes: 2 additions & 5 deletions src/mc_rbdyn/gui/RobotSurface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,8 @@ std::vector<std::string> addSurfaceToGUI(mc_rtc::gui::StateBuilder & gui,
{
const auto & cylinder = dynamic_cast<const mc_rbdyn::CylindricalSurface &>(surface);
publish_surface(mc_rtc::gui::Cylinder(
publishName.value_or(name),
[&cylinder]() {
return mc_rtc::gui::CylinderParameters{cylinder.radius(), cylinder.width()};
},
get_pose, cfg.color));
publishName.value_or(name), [&cylinder]()
{ return mc_rtc::gui::CylinderParameters{cylinder.radius(), cylinder.width()}; }, get_pose, cfg.color));
}
else if(surface.type() == "planar")
{
Expand Down
2 changes: 1 addition & 1 deletion src/mc_robots/json.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,6 @@ static auto registered = []()
mc_rbdyn::RobotLoader::register_object("json", callback);
return true;
}();
}
} // namespace

#endif
2 changes: 1 addition & 1 deletion src/mc_robots/jvrc1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,6 @@ static auto registered = []()
mc_rbdyn::RobotLoader::register_object("JVRC1Fixed", fn_t([]() { return new mc_robots::JVRC1RobotModule(true); }));
return true;
}();
}
} // namespace

#endif
8 changes: 4 additions & 4 deletions src/mc_rtc/iterate_binary_log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,10 +90,10 @@ bool iterate_binary_log(const std::string & f,
}
return keys_str;
}();
if(!callback(IterateBinaryLogData{keys_str, log.records(), events, t,
[&log](mc_rtc::MessagePackBuilder & builder,
const std::vector<std::string> & keys) { log.copy(builder, keys); },
buffer.data(), entrySize, meta}))
if(!callback(
IterateBinaryLogData{keys_str, log.records(), events, t,
[&log](mc_rtc::MessagePackBuilder & builder, const std::vector<std::string> & keys)
{ log.copy(builder, keys); }, buffer.data(), entrySize, meta}))
{
return false;
}
Expand Down
3 changes: 1 addition & 2 deletions src/mc_rtc/loader.in.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,8 +212,7 @@ void Loader::load_libraries(const std::string & class_name,
std::vector<bfs::path> drange;
std::copy(dit, endit, std::back_inserter(drange));
// Sort by newest file
std::sort(drange.begin(), drange.end(),
[](const bfs::path & p1, const bfs::path & p2)
std::sort(drange.begin(), drange.end(), [](const bfs::path & p1, const bfs::path & p2)
{ return bfs::last_write_time(p1) > bfs::last_write_time(p2); });
for(const auto & p : drange)
{
Expand Down
10 changes: 4 additions & 6 deletions src/mc_solver/BoundedSpeedConstr.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,9 @@ struct TVMBoundedSpeedConstr

std::vector<BoundedSpeedData>::iterator getData(const mc_rbdyn::RobotFrame & frame)
{
return std::find_if(data_.begin(), data_.end(),
[&](const auto & d) {
return d.fn->frame().name() == frame.name()
&& d.fn->frame().robot().name() == frame.robot().name();
});
return std::find_if(
data_.begin(), data_.end(), [&](const auto & d)
{ return d.fn->frame().name() == frame.name() && d.fn->frame().robot().name() == frame.robot().name(); });
}

void addBoundedSpeed(TVMQPSolver * solver,
Expand Down Expand Up @@ -391,4 +389,4 @@ static auto registered = mc_solver::ConstraintSetLoader::register_load_function(
}
return ret;
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_solver/CoMIncPlaneConstr.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -277,4 +277,4 @@ static auto registered = mc_solver::ConstraintSetLoader::register_load_function(
solver.robots(), robotIndexFromConfig(config, solver.robots(), "CoMIncPlane"), solver.dt());
return ret;
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_solver/CollisionsConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -629,4 +629,4 @@ static auto registered = mc_solver::ConstraintSetLoader::register_load_function(
ret->addCollisions(solver, collisions);
return ret;
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_solver/CompoundJointConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,4 +208,4 @@ static auto registered = mc_solver::ConstraintSetLoader::register_load_function(
}
else { return std::make_shared<mc_solver::CompoundJointConstraint>(solver.robots(), rIndex, solver.dt()); }
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_solver/ContactConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,4 +106,4 @@ static auto registered = mc_solver::ConstraintSetLoader::register_load_function(
}
return std::make_shared<mc_solver::ContactConstraint>(solver.dt(), cType);
});
}
} // namespace
5 changes: 2 additions & 3 deletions src/mc_solver/TVMQPSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -390,9 +390,8 @@ auto TVMQPSolver::addVirtualContactImpl(const mc_rbdyn::Contact & contact) -> st
[this, contact]() { return desiredContactForce(contact); });
gui_->addElement({"Contacts", "Forces"},
mc_rtc::gui::Force(
fmt::format("{}::{}/{}::{}", r1.name(), f1.name(), r2.name(), f2.name()),
[this, contact]() { return desiredContactForce(contact); },
[&f1]() { return f1.position(); }));
fmt::format("{}::{}/{}::{}", r1.name(), f1.name(), r2.name(), f2.name()), [this, contact]()
{ return desiredContactForce(contact); }, [&f1]() { return f1.position(); }));
}
else
{
Expand Down
3 changes: 1 addition & 2 deletions src/mc_solver/TasksQPSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,8 +98,7 @@ void TasksQPSolver::setContacts(ControllerToken, const std::vector<mc_rbdyn::Con
gui_->addElement({"Contacts", "Forces"},
mc_rtc::gui::Force(
fmt::format("{}::{}/{}::{}", r1, r1S, r2, r2S),
[this, &contact]() { return desiredContactForce(contact); },
[this, &contact]()
[this, &contact]() { return desiredContactForce(contact); }, [this, &contact]()
{ return robots().robot(contact.r1Index()).surfacePose(contact.r1Surface()->name()); }));
}
}
Expand Down
2 changes: 1 addition & 1 deletion src/mc_tasks/AdmittanceTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,4 +167,4 @@ static auto registered = mc_tasks::MetaTaskLoader::register_load_function(
t->load(solver, config);
return t;
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_tasks/BSplineTrajectoryTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,4 +159,4 @@ static auto registered = mc_tasks::MetaTaskLoader::register_load_function(
t->pause(config("paused", false));
return t;
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_tasks/CoMTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,4 +144,4 @@ static auto registered = mc_tasks::MetaTaskLoader::register_load_function(
t->load(solver, config);
return t;
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_tasks/CoPTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,4 +156,4 @@ static auto registered = mc_tasks::MetaTaskLoader::register_load_function(
t->load(solver, config);
return t;
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_tasks/ComplianceTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,4 +207,4 @@ static auto registered = mc_tasks::MetaTaskLoader::register_load_function(
t->load(solver, config);
return t;
});
}
} // namespace
2 changes: 1 addition & 1 deletion src/mc_tasks/DampingTask.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,4 +80,4 @@ static auto registered = mc_tasks::MetaTaskLoader::register_load_function(
t->load(solver, config);
return t;
});
}
} // namespace
Loading

0 comments on commit 29400e0

Please sign in to comment.