Skip to content

Commit

Permalink
Merge branch 'feature/log_multiple_args' into 'master'
Browse files Browse the repository at this point in the history
Log multiple args, also using operator<<()

Closes #24 and #23

See merge request MRT/released/rosinterface_handler!24
  • Loading branch information
poggenhans committed Jun 23, 2020
2 parents 609bc49 + a5f1583 commit 169e832
Show file tree
Hide file tree
Showing 4 changed files with 49 additions and 17 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Expand Up @@ -69,7 +69,7 @@ if (CATKIN_ENABLE_TESTING)
find_package(tf2_ros REQUIRED)
find_package(image_transport REQUIRED)
target_link_libraries(${TEST_TARGET_NAME} ${catkin_LIBRARIES} ${tf2_ros_LIBRARIES} ${image_transport_LIBRARIES} gtest)
target_include_directories(${TEST_TARGET_NAME} PUBLIC ${catkin_INCLUDE_DIRS} ${tf2_ros_INCLUDE_DIRS} ${image_transport_INCLUDE_DIRS} include)
target_include_directories(${TEST_TARGET_NAME} PUBLIC include ${catkin_INCLUDE_DIRS} ${tf2_ros_INCLUDE_DIRS} ${image_transport_INCLUDE_DIRS})
add_dependencies(${TEST_TARGET_NAME} ${catkin_EXPORTED_TARGETS} ${${PROJECT_NAME}_EXPORTED_TARGETS})
set_property(TARGET ${TEST_TARGET_NAME} PROPERTY CXX_STANDARD 14)
set_property(TARGET ${TEST_TARGET_NAME} PROPERTY CXX_STANDARD_REQUIRED ON)
Expand Down
14 changes: 9 additions & 5 deletions include/rosinterface_handler/simple_node_status.hpp
Expand Up @@ -5,6 +5,8 @@
#include <diagnostic_updater/diagnostic_updater.h>
#include <ros/node_handle.h>

#include "utilities.hpp"

namespace rosinterface_handler {
//! Mirrors diagnostic_updater::DiagnosticStatus, but with strong typing
enum class NodeStatus : std::uint8_t {
Expand Down Expand Up @@ -39,12 +41,13 @@ class SimpleNodeStatus {
updater_->force_update();
}

//! Leightweight way to set or report a new status. The status remains until overwritten by a new status.
void set(NodeStatus s, const std::string& msg) {
//! Lightweight way to set or report a new status. The status remains until overwritten by a new status.
template <typename Arg, typename... Args>
void set(NodeStatus s, const Arg& arg, const Args&... Args_) {
bool modified = false;
{
std::lock_guard<std::mutex> g{statusMutex_};
Status newStatus{s, msg};
Status newStatus{s, asString(arg, Args_...)};
modified = status_ != newStatus;
status_ = newStatus;
}
Expand All @@ -56,9 +59,10 @@ class SimpleNodeStatus {

//! Add/overwrite extra information about the status in form of key/value pairs. The information will be shared
//! along with the overall node status. It remains until explicitly cleared or overwritten.
void info(const std::string& name, std::string message) {
template <typename Arg, typename... Args>
void info(const std::string& name, const Arg& arg, const Args&... Args_) {
std::lock_guard<std::mutex> g{statusMutex_};
extraInfo_[name] = std::move(message);
extraInfo_[name] = asString(arg, Args_...);
}

//! Clears previously set information. Returns true on success.
Expand Down
23 changes: 23 additions & 0 deletions include/rosinterface_handler/utilities.hpp
@@ -1,6 +1,7 @@
#pragma once

#include <limits>
#include <sstream>
#include <string>
#include <ros/node_handle.h>
#include <ros/param.h>
Expand Down Expand Up @@ -301,4 +302,26 @@ inline void testMax(const std::string key, std::map<K, T>& val, T max = std::num
}
}

/// \brief Convert at least one argument to a string
/// \tparam Arg Type of required argument
/// \tparam Args Type of additional arguments (optional)
/// \param arg Required argument
/// \param args Additional arguments (optional)
/// \return
template <typename Arg, typename... Args>
inline std::string asString(Arg&& arg, Args&&... Args_) {
std::ostringstream oss;
oss << std::forward<Arg>(arg);
(oss << ... << std::forward<Args>(Args_));
return oss.str();
}

inline std::string asString(std::string&& arg) {
return std::move(arg);
}

inline const std::string& asString(const std::string& arg) {
return arg;
}

} // namespace rosinterface_handler
27 changes: 16 additions & 11 deletions templates/Interface.h.template
Expand Up @@ -119,34 +119,39 @@ $string_representation;
return privateNodeHandle_.getNamespace();
}

/// \brief logs to the debug output. Works also within nodelets. Output is throttled.
/// \brief logs to the debug output. Works also within nodelets.
// NOLINTNEXTLINE(readability-function-size)
inline void logDebug(const std::string& msg) const {
ROS_DEBUG_STREAM_NAMED(nodeNameWithNamespace(), msg);
template <typename Msg, typename... Msgs>
inline void logDebug(const Msg& msg, const Msgs&... Msgs_) const {
ROS_DEBUG_STREAM_NAMED(nodeNameWithNamespace(), rosinterface_handler::asString(msg, Msgs_...));
}

/// \brief logs to the debug output. Works also within nodelets. Output is throttled.
// NOLINTNEXTLINE(readability-function-size)
inline void logInfo(const std::string& msg) const {
ROS_INFO_STREAM_THROTTLE_NAMED(5, nodeNameWithNamespace(), msg);
template <typename Msg, typename... Msgs>
inline void logInfo(const Msg& msg, const Msgs&... Msgs_) const {
ROS_INFO_STREAM_THROTTLE_NAMED(5, nodeNameWithNamespace(), rosinterface_handler::asString(msg, Msgs_...));
}

/// \brief logs to the debug output. Works also within nodelets. Output is throttled.
// NOLINTNEXTLINE(readability-function-size)
inline void logWarn(const std::string& msg) const {
ROS_WARN_STREAM_THROTTLE_NAMED(5, nodeNameWithNamespace(), msg);
template <typename Msg, typename... Msgs>
inline void logWarn(const Msg& msg, const Msgs&... Msgs_) const {
ROS_WARN_STREAM_THROTTLE_NAMED(5, nodeNameWithNamespace(), rosinterface_handler::asString(msg, Msgs_...));
}

/// \brief logs to the error output. Works also within nodelets. Output is throttled.
// NOLINTNEXTLINE(readability-function-size)
inline void logError(const std::string& msg) const {
ROS_ERROR_STREAM_THROTTLE_NAMED(5, nodeNameWithNamespace(), msg);
template <typename Msg, typename... Msgs>
inline void logError(const Msg& msg, const Msgs&... Msgs_) const {
ROS_ERROR_STREAM_THROTTLE_NAMED(5, nodeNameWithNamespace(), rosinterface_handler::asString(msg, Msgs_...));
}

/// \brief logs to the error output. Works also within nodelets. Not throttled! Dont call this in loops!
// NOLINTNEXTLINE(readability-function-size)
inline void logErrorDirect(const std::string& msg) const {
ROS_ERROR_STREAM_NAMED(nodeNameWithNamespace(), msg);
template <typename Msg, typename... Msgs>
inline void logErrorDirect(const Msg& msg, const Msgs&... Msgs_) const {
ROS_ERROR_STREAM_NAMED(nodeNameWithNamespace(), rosinterface_handler::asString(msg, Msgs_...));
}

/// \brief logs subscribed and advertised topics to the command line. Works also within nodelets.
Expand Down

0 comments on commit 169e832

Please sign in to comment.