Skip to content

Commit

Permalink
Revert "Node logger through singleton (warehouse) (#2445)"
Browse files Browse the repository at this point in the history
This reverts commit 6a7b557.
  • Loading branch information
tylerjw committed Nov 9, 2023
1 parent 86403e9 commit 88e6377
Show file tree
Hide file tree
Showing 22 changed files with 109 additions and 282 deletions.
3 changes: 0 additions & 3 deletions moveit_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,6 @@
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_index_cpp</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>rclpy</test_depend>
<test_depend>rcl_interfaces</test_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
8 changes: 1 addition & 7 deletions moveit_core/utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,12 @@ add_library(moveit_utils SHARED
src/lexical_casts.cpp
src/message_checks.cpp
src/rclcpp_utils.cpp
src/logger.cpp
)
target_include_directories(moveit_utils PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/moveit_core>
)
ament_target_dependencies(moveit_utils Boost moveit_msgs rclcpp)
ament_target_dependencies(moveit_utils Boost moveit_msgs)
set_target_properties(moveit_utils PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

install(DIRECTORY include/ DESTINATION include/moveit_core)
Expand All @@ -29,10 +28,5 @@ ament_target_dependencies(moveit_test_utils
srdfdom
urdfdom
urdfdom_headers
rclcpp
)
set_target_properties(moveit_test_utils PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")

if(BUILD_TESTING)
add_subdirectory(test)
endif()
25 changes: 0 additions & 25 deletions moveit_core/utils/test/CMakeLists.txt

This file was deleted.

111 changes: 0 additions & 111 deletions moveit_core/utils/test/rosout_publish_test.py

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,6 @@

#include <moveit_warehouse_export.h>

#include <rclcpp/logger.hpp>

namespace moveit_warehouse
{
typedef warehouse_ros::MessageWithMetadata<moveit_msgs::msg::Constraints>::ConstPtr ConstraintsWithMetadata;
Expand Down Expand Up @@ -85,6 +83,5 @@ class MOVEIT_WAREHOUSE_EXPORT ConstraintsStorage : public MoveItMessageStorage
void createCollections();

ConstraintsCollection constraints_collection_;
rclcpp::Logger logger_;
};
} // namespace moveit_warehouse
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@
#include <moveit_msgs/msg/planning_scene.hpp>
#include <moveit_msgs/msg/motion_plan_request.hpp>
#include <moveit_msgs/msg/robot_trajectory.hpp>
#include <rclcpp/logger.hpp>

#include <moveit_warehouse_export.h>

Expand Down Expand Up @@ -120,6 +119,5 @@ class MOVEIT_WAREHOUSE_EXPORT PlanningSceneStorage : public MoveItMessageStorage
PlanningSceneCollection planning_scene_collection_;
MotionPlanRequestCollection motion_plan_request_collection_;
RobotTrajectoryCollection robot_trajectory_collection_;
rclcpp::Logger logger_;
};
} // namespace moveit_warehouse
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@

#include <moveit/warehouse/moveit_message_storage.h>
#include <moveit_msgs/msg/planning_scene_world.hpp>
#include <rclcpp/logger.hpp>

namespace moveit_warehouse
{
Expand Down Expand Up @@ -71,6 +70,5 @@ class PlanningSceneWorldStorage : public MoveItMessageStorage
void createCollections();

PlanningSceneWorldCollection planning_scene_world_collection_;
rclcpp::Logger logger_;
};
} // namespace moveit_warehouse
2 changes: 0 additions & 2 deletions moveit_ros/warehouse/include/moveit/warehouse/state_storage.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
#include <moveit/warehouse/moveit_message_storage.h>
#include <moveit/macros/class_forward.h>
#include <moveit_msgs/msg/robot_state.hpp>
#include <rclcpp/logger.hpp>

#include <moveit_warehouse_export.h>

Expand Down Expand Up @@ -79,6 +78,5 @@ class MOVEIT_WAREHOUSE_EXPORT RobotStateStorage : public MoveItMessageStorage
void createCollections();

RobotStateCollection state_collection_;
rclcpp::Logger logger_;
};
} // namespace moveit_warehouse
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@
#include <moveit/warehouse/moveit_message_storage.h>
#include <moveit/macros/class_forward.h>
#include <moveit_msgs/msg/trajectory_constraints.hpp>
#include <rclcpp/logger.hpp>

namespace moveit_warehouse
{
Expand Down Expand Up @@ -85,6 +84,5 @@ class TrajectoryConstraintsStorage : public MoveItMessageStorage
void createCollections();

TrajectoryConstraintsCollection constraints_collection_;
rclcpp::Logger logger_;
};
} // namespace moveit_warehouse
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@
#pragma once

#include <string>
#include <rclcpp/logger.hpp>

namespace moveit_warehouse
{
Expand All @@ -53,6 +52,5 @@ class WarehouseConnector
private:
std::string dbexec_;
int child_pid_;
rclcpp::Logger logger_;
};
} // namespace moveit_warehouse
16 changes: 7 additions & 9 deletions moveit_ros/warehouse/src/broadcast.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@
#include <moveit/warehouse/planning_scene_storage.h>
#include <moveit/warehouse/constraints_storage.h>
#include <moveit/warehouse/state_storage.h>
#include <moveit/utils/logger.hpp>
#include <boost/program_options/cmdline.hpp>
#include <boost/program_options/options_description.hpp>
#include <boost/program_options/parsers.hpp>
Expand Down Expand Up @@ -66,7 +65,6 @@ static const std::string CONSTRAINTS_TOPIC = "constraints";
static const std::string STATES_TOPIC = "robot_states";

using namespace std::chrono_literals;
using moveit::getLogger;

int main(int argc, char** argv)
{
Expand All @@ -75,7 +73,7 @@ int main(int argc, char** argv)
node_options.allow_undeclared_parameters(true);
node_options.automatically_declare_parameters_from_overrides(true);
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("publish_warehouse_data", node_options);
moveit::getLoggerMut() = node->get_logger();
const auto logger = node->get_logger();

// time to wait in between publishing messages
double delay = 0.001;
Expand Down Expand Up @@ -142,7 +140,7 @@ int main(int argc, char** argv)
moveit_warehouse::PlanningSceneWithMetadata pswm;
if (pss.getPlanningScene(pswm, scene_name))
{
RCLCPP_INFO(getLogger(), "Publishing scene '%s'",
RCLCPP_INFO(logger, "Publishing scene '%s'",
pswm->lookupString(moveit_warehouse::PlanningSceneStorage::PLANNING_SCENE_ID_NAME).c_str());
pub_scene->publish(static_cast<const moveit_msgs::msg::PlanningScene&>(*pswm));
executor.spin_once(0ns);
Expand All @@ -155,14 +153,14 @@ int main(int argc, char** argv)
std::vector<moveit_warehouse::MotionPlanRequestWithMetadata> planning_queries;
std::vector<std::string> query_names;
pss.getPlanningQueries(planning_queries, query_names, pswm->name);
RCLCPP_INFO(getLogger(), "There are %d planning queries associated to the scene",
RCLCPP_INFO(logger, "There are %d planning queries associated to the scene",
static_cast<int>(planning_queries.size()));
rclcpp::sleep_for(500ms);
for (std::size_t i = 0; i < planning_queries.size(); ++i)
{
if (req)
{
RCLCPP_INFO(getLogger(), "Publishing query '%s'", query_names[i].c_str());
RCLCPP_INFO(logger, "Publishing query '%s'", query_names[i].c_str());
pub_req->publish(static_cast<const moveit_msgs::msg::MotionPlanRequest&>(*planning_queries[i]));
executor.spin_once(0ns);
}
Expand Down Expand Up @@ -196,7 +194,7 @@ int main(int argc, char** argv)
moveit_warehouse::ConstraintsWithMetadata cwm;
if (cs.getConstraints(cwm, cname))
{
RCLCPP_INFO(getLogger(), "Publishing constraints '%s'",
RCLCPP_INFO(logger, "Publishing constraints '%s'",
cwm->lookupString(moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME).c_str());
pub_constr->publish(static_cast<const moveit_msgs::msg::Constraints&>(*cwm));
executor.spin_once(0ns);
Expand All @@ -218,7 +216,7 @@ int main(int argc, char** argv)
moveit_warehouse::RobotStateWithMetadata rswm;
if (rs.getRobotState(rswm, rname))
{
RCLCPP_INFO(getLogger(), "Publishing state '%s'",
RCLCPP_INFO(logger, "Publishing state '%s'",
rswm->lookupString(moveit_warehouse::RobotStateStorage::STATE_NAME).c_str());
pub_state->publish(static_cast<const moveit_msgs::msg::RobotState&>(*rswm));
executor.spin_once(0ns);
Expand All @@ -228,7 +226,7 @@ int main(int argc, char** argv)
}

rclcpp::sleep_for(1s);
RCLCPP_INFO(getLogger(), "Done.");
RCLCPP_INFO(logger, "Done.");

return 0;
}
11 changes: 6 additions & 5 deletions moveit_ros/warehouse/src/constraints_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@
/* Author: Ioan Sucan */

#include <moveit/warehouse/constraints_storage.h>
#include <moveit/utils/logger.hpp>

#include <utility>

Expand All @@ -45,11 +44,13 @@ const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME = "c
const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_GROUP_NAME = "group_id";
const std::string moveit_warehouse::ConstraintsStorage::ROBOT_NAME = "robot_id";

static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.constraints_storage");

using warehouse_ros::Metadata;
using warehouse_ros::Query;

moveit_warehouse::ConstraintsStorage::ConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
: MoveItMessageStorage(std::move(conn)), logger_(moveit::makeChildLogger("moveit_warehouse_constraints_storage"))
: MoveItMessageStorage(std::move(conn))
{
createCollections();
}
Expand Down Expand Up @@ -80,7 +81,7 @@ void moveit_warehouse::ConstraintsStorage::addConstraints(const moveit_msgs::msg
metadata->append(ROBOT_NAME, robot);
metadata->append(CONSTRAINTS_GROUP_NAME, group);
constraints_collection_->insert(msg, metadata);
RCLCPP_DEBUG(logger_, "%s constraints '%s'", replace ? "Replaced" : "Added", msg.name.c_str());
RCLCPP_DEBUG(LOGGER, "%s constraints '%s'", replace ? "Replaced" : "Added", msg.name.c_str());
}

bool moveit_warehouse::ConstraintsStorage::hasConstraints(const std::string& name, const std::string& robot,
Expand Down Expand Up @@ -157,7 +158,7 @@ void moveit_warehouse::ConstraintsStorage::renameConstraints(const std::string&
Metadata::Ptr m = constraints_collection_->createMetadata();
m->append(CONSTRAINTS_ID_NAME, new_name);
constraints_collection_->modifyMetadata(q, m);
RCLCPP_DEBUG(logger_, "Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
RCLCPP_DEBUG(LOGGER, "Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
}

void moveit_warehouse::ConstraintsStorage::removeConstraints(const std::string& name, const std::string& robot,
Expand All @@ -170,5 +171,5 @@ void moveit_warehouse::ConstraintsStorage::removeConstraints(const std::string&
if (!group.empty())
q->append(CONSTRAINTS_GROUP_NAME, group);
unsigned int rem = constraints_collection_->removeMessages(q);
RCLCPP_DEBUG(logger_, "Removed %u Constraints messages (named '%s')", rem, name.c_str());
RCLCPP_DEBUG(LOGGER, "Removed %u Constraints messages (named '%s')", rem, name.c_str());
}
Loading

0 comments on commit 88e6377

Please sign in to comment.