Skip to content

Commit

Permalink
Use child loggers
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw committed Oct 24, 2023
1 parent b436a45 commit ef953a5
Show file tree
Hide file tree
Showing 13 changed files with 50 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@

#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 @@ -83,5 +85,6 @@ 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,6 +41,7 @@
#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 @@ -119,5 +120,6 @@ 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,6 +38,7 @@

#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 @@ -70,5 +71,6 @@ class PlanningSceneWorldStorage : public MoveItMessageStorage
void createCollections();

PlanningSceneWorldCollection planning_scene_world_collection_;
rclcpp::Logger logger_;
};
} // namespace moveit_warehouse
2 changes: 2 additions & 0 deletions moveit_ros/warehouse/include/moveit/warehouse/state_storage.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#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 @@ -78,5 +79,6 @@ 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,6 +39,7 @@
#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 @@ -84,5 +85,6 @@ 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,6 +37,7 @@
#pragma once

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

namespace moveit_warehouse
{
Expand All @@ -52,5 +53,6 @@ class WarehouseConnector
private:
std::string dbexec_;
int child_pid_;
rclcpp::Logger logger_;
};
} // namespace moveit_warehouse
9 changes: 4 additions & 5 deletions moveit_ros/warehouse/src/constraints_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,12 +45,11 @@ 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";

using moveit::get_logger;
using warehouse_ros::Metadata;
using warehouse_ros::Query;

moveit_warehouse::ConstraintsStorage::ConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
: MoveItMessageStorage(std::move(conn))
: MoveItMessageStorage(std::move(conn)), logger_(moveit::make_child_logger("moveit_warehouse_constraints_storage"))
{
createCollections();
}
Expand Down Expand Up @@ -81,7 +80,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(get_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 @@ -158,7 +157,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(get_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 @@ -171,5 +170,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(get_logger(), "Removed %u Constraints messages (named '%s')", rem, name.c_str());
RCLCPP_DEBUG(logger_, "Removed %u Constraints messages (named '%s')", rem, name.c_str());
}
4 changes: 2 additions & 2 deletions moveit_ros/warehouse/src/import_from_text.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,10 +47,10 @@
#include <boost/program_options/variables_map.hpp>
#include <moveit/utils/logger.hpp>

using moveit::get_logger;

static const std::string ROBOT_DESCRIPTION = "robot_description";

using moveit::get_logger;

void parseStart(std::istream& in, planning_scene_monitor::PlanningSceneMonitor* psm,
moveit_warehouse::RobotStateStorage* rs)
{
Expand Down
27 changes: 13 additions & 14 deletions moveit_ros/warehouse/src/planning_scene_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,12 +45,11 @@ const std::string moveit_warehouse::PlanningSceneStorage::DATABASE_NAME = "movei
const std::string moveit_warehouse::PlanningSceneStorage::PLANNING_SCENE_ID_NAME = "planning_scene_id";
const std::string moveit_warehouse::PlanningSceneStorage::MOTION_PLAN_REQUEST_ID_NAME = "motion_request_id";

using moveit::get_logger;
using warehouse_ros::Metadata;
using warehouse_ros::Query;

moveit_warehouse::PlanningSceneStorage::PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn)
: MoveItMessageStorage(std::move(conn))
: MoveItMessageStorage(std::move(conn)), logger_(moveit::make_child_logger("moveit_warehouse_planning_scene_storage"))
{
createCollections();
}
Expand Down Expand Up @@ -85,7 +84,7 @@ void moveit_warehouse::PlanningSceneStorage::addPlanningScene(const moveit_msgs:
Metadata::Ptr metadata = planning_scene_collection_->createMetadata();
metadata->append(PLANNING_SCENE_ID_NAME, scene.name);
planning_scene_collection_->insert(scene, metadata);
RCLCPP_DEBUG(get_logger(), "%s scene '%s'", replace ? "Replaced" : "Added", scene.name.c_str());
RCLCPP_DEBUG(logger_, "%s scene '%s'", replace ? "Replaced" : "Added", scene.name.c_str());
}

bool moveit_warehouse::PlanningSceneStorage::hasPlanningScene(const std::string& name) const
Expand Down Expand Up @@ -173,7 +172,7 @@ moveit_warehouse::PlanningSceneStorage::addNewPlanningRequest(const moveit_msgs:
metadata->append(PLANNING_SCENE_ID_NAME, scene_name);
metadata->append(MOTION_PLAN_REQUEST_ID_NAME, id);
motion_plan_request_collection_->insert(planning_query, metadata);
RCLCPP_DEBUG(get_logger(), "Saved planning query '%s' for scene '%s'", id.c_str(), scene_name.c_str());
RCLCPP_DEBUG(logger_, "Saved planning query '%s' for scene '%s'", id.c_str(), scene_name.c_str());
return id;
}

Expand Down Expand Up @@ -231,7 +230,7 @@ bool moveit_warehouse::PlanningSceneStorage::getPlanningScene(PlanningSceneWithM
std::vector<PlanningSceneWithMetadata> planning_scenes = planning_scene_collection_->queryList(q, false);
if (planning_scenes.empty())
{
RCLCPP_WARN(get_logger(), "Planning scene '%s' was not found in the database", scene_name.c_str());
RCLCPP_WARN(logger_, "Planning scene '%s' was not found in the database", scene_name.c_str());
return false;
}
scene_m = planning_scenes.back();
Expand All @@ -251,7 +250,7 @@ bool moveit_warehouse::PlanningSceneStorage::getPlanningQuery(MotionPlanRequestW
std::vector<MotionPlanRequestWithMetadata> planning_queries = motion_plan_request_collection_->queryList(q, false);
if (planning_queries.empty())
{
RCLCPP_ERROR(get_logger(), "Planning query '%s' not found for scene '%s'", query_name.c_str(), scene_name.c_str());
RCLCPP_ERROR(logger_, "Planning query '%s' not found for scene '%s'", query_name.c_str(), scene_name.c_str());
return false;
}
else
Expand Down Expand Up @@ -369,7 +368,7 @@ void moveit_warehouse::PlanningSceneStorage::renamePlanningScene(const std::stri
Metadata::Ptr m = planning_scene_collection_->createMetadata();
m->append(PLANNING_SCENE_ID_NAME, new_scene_name);
planning_scene_collection_->modifyMetadata(q, m);
RCLCPP_DEBUG(get_logger(), "Renamed planning scene from '%s' to '%s'", old_scene_name.c_str(), new_scene_name.c_str());
RCLCPP_DEBUG(logger_, "Renamed planning scene from '%s' to '%s'", old_scene_name.c_str(), new_scene_name.c_str());
}

void moveit_warehouse::PlanningSceneStorage::renamePlanningQuery(const std::string& scene_name,
Expand All @@ -382,7 +381,7 @@ void moveit_warehouse::PlanningSceneStorage::renamePlanningQuery(const std::stri
Metadata::Ptr m = motion_plan_request_collection_->createMetadata();
m->append(MOTION_PLAN_REQUEST_ID_NAME, new_query_name);
motion_plan_request_collection_->modifyMetadata(q, m);
RCLCPP_DEBUG(get_logger(), "Renamed planning query for scene '%s' from '%s' to '%s'", scene_name.c_str(),
RCLCPP_DEBUG(logger_, "Renamed planning query for scene '%s' from '%s' to '%s'", scene_name.c_str(),
old_query_name.c_str(), new_query_name.c_str());
}

Expand All @@ -392,7 +391,7 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningScene(const std::stri
Query::Ptr q = planning_scene_collection_->createQuery();
q->append(PLANNING_SCENE_ID_NAME, scene_name);
unsigned int rem = planning_scene_collection_->removeMessages(q);
RCLCPP_DEBUG(get_logger(), "Removed %u PlanningScene messages (named '%s')", rem, scene_name.c_str());
RCLCPP_DEBUG(logger_, "Removed %u PlanningScene messages (named '%s')", rem, scene_name.c_str());
}

void moveit_warehouse::PlanningSceneStorage::removePlanningQueries(const std::string& scene_name)
Expand All @@ -401,7 +400,7 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningQueries(const std::st
Query::Ptr q = motion_plan_request_collection_->createQuery();
q->append(PLANNING_SCENE_ID_NAME, scene_name);
unsigned int rem = motion_plan_request_collection_->removeMessages(q);
RCLCPP_DEBUG(get_logger(), "Removed %u MotionPlanRequest messages for scene '%s'", rem, scene_name.c_str());
RCLCPP_DEBUG(logger_, "Removed %u MotionPlanRequest messages for scene '%s'", rem, scene_name.c_str());
}

void moveit_warehouse::PlanningSceneStorage::removePlanningQuery(const std::string& scene_name,
Expand All @@ -412,16 +411,16 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningQuery(const std::stri
q->append(PLANNING_SCENE_ID_NAME, scene_name);
q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
unsigned int rem = motion_plan_request_collection_->removeMessages(q);
RCLCPP_DEBUG(get_logger(), "Removed %u MotionPlanRequest messages for scene '%s', query '%s'", rem,
scene_name.c_str(), query_name.c_str());
RCLCPP_DEBUG(logger_, "Removed %u MotionPlanRequest messages for scene '%s', query '%s'", rem, scene_name.c_str(),
query_name.c_str());
}

void moveit_warehouse::PlanningSceneStorage::removePlanningResults(const std::string& scene_name)
{
Query::Ptr q = robot_trajectory_collection_->createQuery();
q->append(PLANNING_SCENE_ID_NAME, scene_name);
unsigned int rem = robot_trajectory_collection_->removeMessages(q);
RCLCPP_DEBUG(get_logger(), "Removed %u RobotTrajectory messages for scene '%s'", rem, scene_name.c_str());
RCLCPP_DEBUG(logger_, "Removed %u RobotTrajectory messages for scene '%s'", rem, scene_name.c_str());
}

void moveit_warehouse::PlanningSceneStorage::removePlanningResults(const std::string& scene_name,
Expand All @@ -431,6 +430,6 @@ void moveit_warehouse::PlanningSceneStorage::removePlanningResults(const std::st
q->append(PLANNING_SCENE_ID_NAME, scene_name);
q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
unsigned int rem = robot_trajectory_collection_->removeMessages(q);
RCLCPP_DEBUG(get_logger(), "Removed %u RobotTrajectory messages for scene '%s', query '%s'", rem, scene_name.c_str(),
RCLCPP_DEBUG(logger_, "Removed %u RobotTrajectory messages for scene '%s', query '%s'", rem, scene_name.c_str(),
query_name.c_str());
}
8 changes: 4 additions & 4 deletions moveit_ros/warehouse/src/planning_scene_world_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,12 +42,12 @@
const std::string moveit_warehouse::PlanningSceneWorldStorage::DATABASE_NAME = "moveit_planning_scene_worlds";
const std::string moveit_warehouse::PlanningSceneWorldStorage::PLANNING_SCENE_WORLD_ID_NAME = "world_id";

using moveit::get_logger;
using warehouse_ros::Metadata;
using warehouse_ros::Query;

moveit_warehouse::PlanningSceneWorldStorage::PlanningSceneWorldStorage(warehouse_ros::DatabaseConnection::Ptr conn)
: MoveItMessageStorage(std::move(conn))
, logger_(moveit::make_child_logger("moveit_warehouse_planning_scene_world_storage"))
{
createCollections();
}
Expand Down Expand Up @@ -77,7 +77,7 @@ void moveit_warehouse::PlanningSceneWorldStorage::addPlanningSceneWorld(const mo
Metadata::Ptr metadata = planning_scene_world_collection_->createMetadata();
metadata->append(PLANNING_SCENE_WORLD_ID_NAME, name);
planning_scene_world_collection_->insert(msg, metadata);
RCLCPP_DEBUG(get_logger(), "%s planning scene world '%s'", replace ? "Replaced" : "Added", name.c_str());
RCLCPP_DEBUG(logger_, "%s planning scene world '%s'", replace ? "Replaced" : "Added", name.c_str());
}

bool moveit_warehouse::PlanningSceneWorldStorage::hasPlanningSceneWorld(const std::string& name) const
Expand Down Expand Up @@ -133,13 +133,13 @@ void moveit_warehouse::PlanningSceneWorldStorage::renamePlanningSceneWorld(const
Metadata::Ptr m = planning_scene_world_collection_->createMetadata();
m->append(PLANNING_SCENE_WORLD_ID_NAME, new_name);
planning_scene_world_collection_->modifyMetadata(q, m);
RCLCPP_DEBUG(get_logger(), "Renamed planning scene world from '%s' to '%s'", old_name.c_str(), new_name.c_str());
RCLCPP_DEBUG(logger_, "Renamed planning scene world from '%s' to '%s'", old_name.c_str(), new_name.c_str());
}

void moveit_warehouse::PlanningSceneWorldStorage::removePlanningSceneWorld(const std::string& name)
{
Query::Ptr q = planning_scene_world_collection_->createQuery();
q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
unsigned int rem = planning_scene_world_collection_->removeMessages(q);
RCLCPP_DEBUG(get_logger(), "Removed %u PlanningSceneWorld messages (named '%s')", rem, name.c_str());
RCLCPP_DEBUG(logger_, "Removed %u PlanningSceneWorld messages (named '%s')", rem, name.c_str());
}
9 changes: 4 additions & 5 deletions moveit_ros/warehouse/src/state_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,12 +44,11 @@ const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_r
const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id";
const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id";

using moveit::get_logger;
using warehouse_ros::Metadata;
using warehouse_ros::Query;

moveit_warehouse::RobotStateStorage::RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
: MoveItMessageStorage(std::move(conn))
: MoveItMessageStorage(std::move(conn)), logger_(moveit::make_child_logger("moveit_warehouse_robot_state_storage"))
{
createCollections();
}
Expand Down Expand Up @@ -79,7 +78,7 @@ void moveit_warehouse::RobotStateStorage::addRobotState(const moveit_msgs::msg::
metadata->append(STATE_NAME, name);
metadata->append(ROBOT_NAME, robot);
state_collection_->insert(msg, metadata);
RCLCPP_DEBUG(get_logger(), "%s robot state '%s'", replace ? "Replaced" : "Added", name.c_str());
RCLCPP_DEBUG(logger_, "%s robot state '%s'", replace ? "Replaced" : "Added", name.c_str());
}

bool moveit_warehouse::RobotStateStorage::hasRobotState(const std::string& name, const std::string& robot) const
Expand Down Expand Up @@ -143,7 +142,7 @@ void moveit_warehouse::RobotStateStorage::renameRobotState(const std::string& ol
Metadata::Ptr m = state_collection_->createMetadata();
m->append(STATE_NAME, new_name);
state_collection_->modifyMetadata(q, m);
RCLCPP_DEBUG(get_logger(), "Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
RCLCPP_DEBUG(logger_, "Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
}

void moveit_warehouse::RobotStateStorage::removeRobotState(const std::string& name, const std::string& robot)
Expand All @@ -153,5 +152,5 @@ void moveit_warehouse::RobotStateStorage::removeRobotState(const std::string& na
if (!robot.empty())
q->append(ROBOT_NAME, robot);
unsigned int rem = state_collection_->removeMessages(q);
RCLCPP_DEBUG(get_logger(), "Removed %u RobotState messages (named '%s')", rem, name.c_str());
RCLCPP_DEBUG(logger_, "Removed %u RobotState messages (named '%s')", rem, name.c_str());
}
8 changes: 4 additions & 4 deletions moveit_ros/warehouse/src/trajectory_constraints_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,12 +45,12 @@ const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_ID
const std::string moveit_warehouse::TrajectoryConstraintsStorage::CONSTRAINTS_GROUP_NAME = "group_id";
const std::string moveit_warehouse::TrajectoryConstraintsStorage::ROBOT_NAME = "robot_id";

using moveit::get_logger;
using warehouse_ros::Metadata;
using warehouse_ros::Query;

moveit_warehouse::TrajectoryConstraintsStorage::TrajectoryConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
: MoveItMessageStorage(std::move(conn))
, logger_(moveit::make_child_logger("moveit_warehouse_trajectory_constraints_storage"))
{
createCollections();
}
Expand Down Expand Up @@ -83,7 +83,7 @@ void moveit_warehouse::TrajectoryConstraintsStorage::addTrajectoryConstraints(
metadata->append(ROBOT_NAME, robot);
metadata->append(CONSTRAINTS_GROUP_NAME, group);
constraints_collection_->insert(msg, metadata);
RCLCPP_DEBUG(get_logger(), "%s constraints '%s'", replace ? "Replaced" : "Added", name.c_str());
RCLCPP_DEBUG(logger_, "%s constraints '%s'", replace ? "Replaced" : "Added", name.c_str());
}

bool moveit_warehouse::TrajectoryConstraintsStorage::hasTrajectoryConstraints(const std::string& name,
Expand Down Expand Up @@ -165,7 +165,7 @@ void moveit_warehouse::TrajectoryConstraintsStorage::renameTrajectoryConstraints
Metadata::Ptr m = constraints_collection_->createMetadata();
m->append(CONSTRAINTS_ID_NAME, new_name);
constraints_collection_->modifyMetadata(q, m);
RCLCPP_DEBUG(get_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::TrajectoryConstraintsStorage::removeTrajectoryConstraints(const std::string& name,
Expand All @@ -179,5 +179,5 @@ void moveit_warehouse::TrajectoryConstraintsStorage::removeTrajectoryConstraints
if (!group.empty())
q->append(CONSTRAINTS_GROUP_NAME, group);
unsigned int rem = constraints_collection_->removeMessages(q);
RCLCPP_DEBUG(get_logger(), "Removed %u TrajectoryConstraints messages (named '%s')", rem, name.c_str());
RCLCPP_DEBUG(logger_, "Removed %u TrajectoryConstraints messages (named '%s')", rem, name.c_str());
}
Loading

0 comments on commit ef953a5

Please sign in to comment.