Skip to content

Commit

Permalink
fix: clang compiler errors
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidPL1 committed Oct 20, 2023
1 parent e533295 commit 582053b
Show file tree
Hide file tree
Showing 30 changed files with 299 additions and 299 deletions.
1 change: 1 addition & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ Checks: 'performance-*,
modernize-redundant-void-arg,
modernize-use-nullptr,
modernize-use-default,
modernize-use-emplace,
modernize-use-override,
modernize-use-using,
modernize-loop-convert,
Expand Down
6 changes: 3 additions & 3 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
repos:
# Standard hooks
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v4.2.0
rev: v4.5.0
hooks:
# - id: check-added-large-files
- id: check-case-conflict
Expand All @@ -28,7 +28,7 @@ repos:
- id: trailing-whitespace

- repo: https://github.com/alessandrojcm/commitlint-pre-commit-hook
rev: v9.4.0
rev: v9.5.0
hooks:
- id: commitlint
stages: [commit-msg]
Expand All @@ -39,7 +39,7 @@ repos:
- id: clang-format
name: clang-format
description: Format files with ClangFormat.
entry: clang-format-10
entry: clang-format
language: system
files: \.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|m|proto|vert)$
args: ["-fallback-style=none", "-i"]
Expand Down
8 changes: 3 additions & 5 deletions mujoco_ros/include/mujoco_ros/array_safety.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,7 @@
//
// They do not perform runtime bound checks.

namespace mujoco {
namespace sample_util {
namespace mujoco::sample_util {

// returns sizeof(arr)
// use instead of sizeof() to avoid unintended array-to-pointer decay
Expand Down Expand Up @@ -64,7 +63,7 @@ static inline std::size_t strlen_arr(const char (&str)[N])
// like std::sprintf but will not write beyond the bound of dest
// dest is guaranteed to be null-terminated
template <std::size_t N>
static inline int sprintf_arr(char (&dest)[N], const char *format, ...)
__attribute__((__format__(__printf__, 2, 0))) static inline int sprintf_arr(char (&dest)[N], const char *format, ...)
{
std::va_list vargs;
va_start(vargs, format);
Expand Down Expand Up @@ -105,7 +104,6 @@ static inline char *strcpy_arr(char (&dest)[N], const char *src)
return &dest[0];
}

} // namespace sample_util
} // namespace mujoco
} // namespace mujoco::sample_util

#endif // MUJOCO_SAMPLE_ARRAY_SAFETY_H_
6 changes: 3 additions & 3 deletions mujoco_ros/include/mujoco_ros/mujoco_env.h
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ class MujocoEnv
* @brief Construct a new Mujoco Env object.
*
*/
MujocoEnv(std::string admin_hash = std::string());
MujocoEnv(const std::string &admin_hash = std::string());
~MujocoEnv();

MujocoEnv(const MujocoEnv &) = delete;
Expand Down Expand Up @@ -257,11 +257,11 @@ class MujocoEnv
void runControlCbs();
void runPassiveCbs();

bool togglePaused(bool paused, std::string admin_hash = std::string());
bool togglePaused(bool paused, const std::string &admin_hash = std::string());

GlfwAdapter *gui_adapter_ = nullptr;

void runRenderCbs(mjModelPtr model, mjDataPtr data, mjvScene *scene);
void runRenderCbs(mjvScene *scene);
bool step(int num_steps = 1, bool blocking = true);

protected:
Expand Down
14 changes: 6 additions & 8 deletions mujoco_ros/include/mujoco_ros/offscreen_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

#pragma once

#include <math.h>
#include <cmath>

#include <mujoco_ros/common_types.h>

Expand All @@ -48,16 +48,15 @@
#include <tf2_ros/transform_listener.h>
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"

namespace mujoco_ros {
namespace rendering {
namespace mujoco_ros::rendering {

class OffscreenCamera
{
public:
OffscreenCamera(const uint8_t cam_id, const std::string cam_name, const int width, const int height,
OffscreenCamera(const uint8_t cam_id, const std::string &cam_name, const int width, const int height,
const streamType stream_type, const bool use_segid, const float pub_freq,
image_transport::ImageTransport *it, ros::NodeHandlePtr parent_nh,
const mujoco_ros::mjModelPtr model, mujoco_ros::mjDataPtr data, mujoco_ros::MujocoEnv *env_ptr);
image_transport::ImageTransport *it, ros::NodeHandle *parent_nh, const mjModel *model, mjData *data,
mujoco_ros::MujocoEnv *env_ptr);

~OffscreenCamera()
{
Expand Down Expand Up @@ -108,5 +107,4 @@ class OffscreenCamera
// void publishCameraInfo(ros::Time &last_update_time);
};

} // end namespace rendering
} // namespace mujoco_ros
} // end namespace mujoco_ros::rendering
36 changes: 18 additions & 18 deletions mujoco_ros/include/mujoco_ros/plugin_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class MujocoPlugin
void init(const XmlRpc::XmlRpcValue &config, ros::NodeHandlePtr nh, MujocoEnvPtr env_ptr)
{
rosparam_config_ = config;
node_handle_ = nh;
node_handle_ = std::move(nh);
env_ptr_ = env_ptr;
type_ = static_cast<std::string>(rosparam_config_["type"]);
};
Expand All @@ -66,7 +66,7 @@ class MujocoPlugin
* @return true if plugin could be loaded without errors.
* @return false if errors occurred during loading.
*/
bool safe_load(mjModelPtr m, mjDataPtr d)
bool safe_load(const mjModel *m, mjData *d)
{
loading_successful_ = load(m, d);
if (!loading_successful_)
Expand All @@ -91,48 +91,48 @@ class MujocoPlugin
* To apply control, write into \c mjData.ctrl, \c mjData.qfrc_applied and/or \c mjData.xfrc_applied.
* If defined, this function will be called by the mujoco step function at the appropriate time.
*
* @param[in] model pointer to mjModel.
* @param[in] model pointer to const mjModel.
* @param[in] data pointer to mjData.
*/
virtual void controlCallback(mjModelPtr /*model*/, mjDataPtr /*data*/){};
virtual void controlCallback(const mjModel * /*model*/, mjData * /*data*/){};

/**
* @brief Override this function to compute and apply custom passive (i.e. non-controlled) forces.
* This callback should add to the vector \c mjData.qfrc_passive instead of overwriting it, otherwise
* the standard passive forces will be lost.
*
* @param[in] model pointer to mjModel.
* @param[in] model pointer to const mjModel.
* @param[in] data pointer to mjData.
*/
virtual void passiveCallback(mjModelPtr /*model*/, mjDataPtr /*data*/){};
virtual void passiveCallback(const mjModel * /*model*/, mjData * /*data*/){};

/**
* @brief Override this callback to add custom visualisations to the scene.
*
* @param[in] model pointer to mjModel.
* @param[in] model pointer to const mjModel.
* @param[in] data pointer to mjData.
* @param[in] scene pointer to mjvScene.
*/
virtual void renderCallback(mjModelPtr /*model*/, mjDataPtr /*data*/, mjvScene * /*scene*/){};
virtual void renderCallback(const mjModel * /*model*/, mjData * /*data*/, mjvScene * /*scene*/){};

/**
* @brief Override this callback to add custom behavior at the end of a mujoco_ros simulation step.
* Note that unlike `controlCallback` and `passiveCallback` this callback will not be called when mujoco runs
* individual sub-steps.
*
* @param[in] model pointer to mjModel.
* @param[in] model pointer to const mjModel.
* @param[in] data pointer to mjData.
*/
virtual void lastStageCallback(mjModelPtr /*model*/, mjDataPtr /*data*/){};
virtual void lastStageCallback(const mjModel * /*model*/, mjData * /*data*/){};

/**
* @brief Override this callback to add custom behavior when a geom has been changed in the model.
*
* @param[in] model pointer to mjModel.
* @param[in] model pointer to const mjModel.
* @param[in] data pointer to mjData.
* @param[in] geom_id id of the geom thas has been changed.
*/
virtual void onGeomChanged(mjModelPtr /*model*/, mjDataPtr /*data*/, const int /*geom_id*/){};
virtual void onGeomChanged(const mjModel * /*model*/, mjData * /*data*/, const int /*geom_id*/){};

protected:
/**
Expand All @@ -143,7 +143,7 @@ class MujocoPlugin
* @return true on succesful load.
* @return false if load was not successful.
*/
virtual bool load(mjModelPtr m, mjDataPtr d) = 0;
virtual bool load(const mjModel *m, mjData *d) = 0;

/**
* @brief Called on reset.
Expand All @@ -154,7 +154,7 @@ class MujocoPlugin
bool loading_successful_ = false;

protected:
MujocoPlugin() {}
MujocoPlugin() = default;
XmlRpc::XmlRpcValue rosparam_config_;
ros::NodeHandlePtr node_handle_;
MujocoEnvPtr env_ptr_;
Expand All @@ -168,7 +168,7 @@ namespace plugin_utils {
* @param[in] nh Pointer to nodehandle where to first look for the plugin config.
* @param[inout] plugin_config_rpc If any configuration is found, it is stored in this variable.
*/
bool parsePlugins(ros::NodeHandlePtr nh, XmlRpc::XmlRpcValue &plugin_config_rpc);
bool parsePlugins(const ros::NodeHandle *nh, XmlRpc::XmlRpcValue &plugin_config_rpc);

/**
* @brief Calls registerPlugin for each plugin defined in \c config_rpc.
Expand All @@ -177,8 +177,8 @@ bool parsePlugins(ros::NodeHandlePtr nh, XmlRpc::XmlRpcValue &plugin_config_rpc)
* @param[in] config_rpc config of at least one plugin to load.
* @param[inout] plugins vector of plugins. If successfully initialized, the plugins are appended to the vector.
*/
void registerPlugins(ros::NodeHandlePtr nh, XmlRpc::XmlRpcValue &config_rpc, std::vector<MujocoPluginPtr> &plugins,
MujocoEnvPtr env);
void registerPlugins(ros::NodeHandlePtr &nh, XmlRpc::XmlRpcValue &config_rpc, std::vector<MujocoPluginPtr> &plugins,
MujocoEnv *env);

/**
* @brief Loads a MujocoPlugin defined in \c config_rpc via pluginlib and registers it in the passed plugin vector for
Expand All @@ -190,7 +190,7 @@ void registerPlugins(ros::NodeHandlePtr nh, XmlRpc::XmlRpcValue &config_rpc, std
* @return true if initializing the plugin was successful, false otherwise.
*/
bool registerPlugin(ros::NodeHandlePtr nh, XmlRpc::XmlRpcValue &config_rpc, std::vector<MujocoPluginPtr> &plugins,
MujocoEnvPtr env);
MujocoEnv *env);

void unloadPluginloader();
void initPluginLoader();
Expand Down
2 changes: 1 addition & 1 deletion mujoco_ros/include/mujoco_ros/util.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ static inline int jointName2id(mjModel *m, const std::string &joint_name,
const std::string &robot_namespace = std::string())
{
int result = mj_name2id(m, mjOBJ_JOINT, joint_name.c_str());
if (result == -1 && robot_namespace.size() > 0) {
if (result == -1 && !robot_namespace.empty()) {
ROS_DEBUG_STREAM("Trying to find without namespace (" << joint_name.substr(robot_namespace.size()) << ")");
result = mj_name2id(m, mjOBJ_JOINT, joint_name.substr(robot_namespace.size()).c_str());
}
Expand Down
2 changes: 1 addition & 1 deletion mujoco_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,6 @@
<test_depend>rostest</test_depend>

<export>
<mujoco_ros plugin="${prefix}/test/test_plugin/test_plugin.xml" />
<mujoco_ros plugin="${prefix}/test_plugin.xml" />
</export>
</package>
17 changes: 8 additions & 9 deletions mujoco_ros/src/callbacks.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,28 +125,28 @@ void MujocoEnv::onStepGoal(const mujoco_ros_msgs::StepGoalConstPtr &goal)
void MujocoEnv::runControlCbs()
{
for (const auto &plugin : this->cb_ready_plugins_) {
plugin->controlCallback(this->model_, this->data_);
plugin->controlCallback(this->model_.get(), this->data_.get());
}
}

void MujocoEnv::runPassiveCbs()
{
for (const auto &plugin : this->cb_ready_plugins_) {
plugin->passiveCallback(this->model_, this->data_);
plugin->passiveCallback(this->model_.get(), this->data_.get());
}
}

void MujocoEnv::runRenderCbs(mjModelPtr model, mjDataPtr data, mjvScene *scene)
void MujocoEnv::runRenderCbs(mjvScene *scene)
{
for (const auto &plugin : this->cb_ready_plugins_) {
plugin->renderCallback(model, data, scene);
plugin->renderCallback(this->model_.get(), this->data_.get(), scene);
}
}

void MujocoEnv::runLastStageCbs()
{
for (const auto &plugin : this->cb_ready_plugins_) {
plugin->lastStageCallback(this->model_, this->data_);
plugin->lastStageCallback(this->model_.get(), this->data_.get());
}
}

Expand Down Expand Up @@ -287,7 +287,7 @@ bool MujocoEnv::setBodyStateCB(mujoco_ros_msgs::SetBodyState::Request &req,
// Set freejoint position and quaternion
if (req.set_pose && !req.reset_qpos) {
bool valid_pose = true;
if (req.state.pose.header.frame_id != "" && req.state.pose.header.frame_id != "world") {
if (!req.state.pose.header.frame_id.empty() && req.state.pose.header.frame_id != "world") {
try {
tf_bufferPtr_->transform<geometry_msgs::PoseStamped>(req.state.pose, target_pose, "world");
} catch (tf2::TransformException &ex) {
Expand Down Expand Up @@ -337,10 +337,9 @@ bool MujocoEnv::setBodyStateCB(mujoco_ros_msgs::SetBodyState::Request &req,
// Set freejoint twist
if (req.set_twist) {
// Only pose can be transformed. Twist will be ignored!
if (req.state.twist.header.frame_id != "" && req.state.twist.header.frame_id != "world") {
if (!req.state.twist.header.frame_id.empty() && req.state.twist.header.frame_id != "world") {
std::string error_msg("Transforming twists from other frames is not supported! Not setting twist.");
ROS_WARN_STREAM_COND(req.state.twist.header.frame_id != "" && req.state.twist.header.frame_id != "world",
error_msg);
ROS_WARN_STREAM(error_msg);
full_error_msg += error_msg + '\n';
resp.success = false;
} else {
Expand Down
7 changes: 1 addition & 6 deletions mujoco_ros/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <mujoco/mujoco.h>

#include <boost/program_options.hpp>
#include <signal.h>
#include <csignal>
#include <thread>

namespace {
Expand All @@ -55,11 +55,6 @@ void sigint_handler(int /*sig*/)
namespace po = boost::program_options;
namespace mju = ::mujoco::sample_util;

// constants
const double syncMisalign = 0.1; // maximum mis-alignment before re-sync (simulation seconds)
const double simRefreshFraction = 0.7; // fraction of refresh available for simulation
const int kErrorLength = 1024; // load error string length

using Seconds = std::chrono::duration<double>;

} // anonymous namespace
Expand Down
Loading

0 comments on commit 582053b

Please sign in to comment.