Skip to content

Commit

Permalink
Using THROTTLE macros
Browse files Browse the repository at this point in the history
  • Loading branch information
RoboticsYY committed Jan 15, 2020
1 parent 982ece5 commit 1ff5ead
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,6 @@
#include <moveit/occupancy_map_monitor/occupancy_map_monitor.h>
// #include <XmlRpcException.h>
#include <boost/bind.hpp>
#include <rcutils/logging_macros.h>
#include <rcutils/time.h>

namespace occupancy_map_monitor
{
Expand Down Expand Up @@ -288,7 +286,8 @@ bool OccupancyMapMonitor::getShapeTransformCache(std::size_t index, const std::s
std::map<ShapeHandle, ShapeHandle>::const_iterator jt = mesh_handles_[index].find(it.first);
if (jt == mesh_handles_[index].end())
{
RCUTILS_LOG_ERROR_THROTTLE(rcutils_steady_time_now, 1, "Incorrect mapping of mesh handles");
rclcpp::Clock steady_clock(RCL_STEADY_TIME);
RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000, "Incorrect mapping of mesh handles");
return false;
}
else
Expand Down
5 changes: 3 additions & 2 deletions moveit_ros/occupancy_map_monitor/src/occupancy_map_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,14 +52,15 @@ static void publishOctomap(rclcpp::Publisher<octomap_msgs::msg::Octomap>::Shared
map.header.stamp = rclcpp::Clock().now();

server->getOcTreePtr()->lockRead();
rclcpp::Clock steady_clock(RCL_STEADY_TIME);
try
{
if (!octomap_msgs::binaryMapToMsgData(*server->getOcTreePtr(), map.data))
RCUTILS_LOG_ERROR_THROTTLE(rcutils_steady_time_now, 1, "Could not generate OctoMap message");
RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000, "Could not generate OctoMap message");
}
catch (...)
{
RCUTILS_LOG_ERROR_THROTTLE(rcutils_steady_time_now, 1, "Exception thrown while generating OctoMap message");
RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000, "Exception thrown while generating OctoMap message");
}
server->getOcTreePtr()->unlockRead();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,8 +80,9 @@ bool OccupancyMapUpdater::updateTransformCache(const std::string& target_frame,
return transform_provider_callback_(target_frame, target_time, transform_cache_);
else
{
RCUTILS_LOG_ERROR_THROTTLE(rcutils_steady_time_now, 1,
"No callback provided for updating the transform cache for octomap updaters");
rclcpp::Clock steady_clock(RCL_STEADY_TIME);
RCLCPP_WARN_THROTTLE(LOGGER, steady_clock, 1000,
"No callback provided for updating the transform cache for octomap updaters");
return false;
}
}
Expand Down

0 comments on commit 1ff5ead

Please sign in to comment.