Skip to content

Commit

Permalink
Unify log names (#2720)
Browse files Browse the repository at this point in the history
Co-authored-by: Abishalini Sivaraman <[email protected]>
  • Loading branch information
sjahr and Abishalini authored Mar 15, 2024
1 parent e65491e commit f06f38b
Show file tree
Hide file tree
Showing 166 changed files with 201 additions and 184 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection.world_allvalid");
return moveit::getLogger("moveit.core.collision_detection.env_allvalid");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/collision_detection/src/collision_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection_common");
return moveit::getLogger("moveit.core.collision_detection.collision_common");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/collision_detection/src/collision_env.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection_env");
return moveit::getLogger("moveit.core.collision_detection_env");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/collision_detection/src/collision_matrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection_matrix");
return moveit::getLogger("moveit.core.collision_detection_matrix");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection_octomap_filter");
return moveit::getLogger("moveit.core.collision_detection_octomap_filter");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection_plugin_cache");
return moveit::getLogger("moveit.core.collision_detection_plugin_cache");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/collision_detection/src/world.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection_world");
return moveit::getLogger("moveit.core.collision_detection_world");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,6 @@ Eigen::Isometry3d urdfPose2Eigen(const urdf::Pose& pose)

rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection_bullet");
return moveit::getLogger("moveit.core.collision_detection_bullet");
}
} // namespace collision_detection_bullet
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ namespace cb = collision_detection_bullet;

rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_detection.bullet_test");
return moveit::getLogger("moveit.core.collision_detection.bullet_test");
}

/** \brief Brings the panda robot in user defined home position */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("moveit_collision_detection_fcl");
return moveit::getLogger("moveit.core.moveit_collision_detection_fcl");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("moveit_collision_detection_fcl");
return moveit::getLogger("moveit.core.collision_detection_fcl");
}

// Check whether this FCL version supports the requested computations
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/collision_detection_fcl/test/test_fcl_env.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ inline void setToHome(moveit::core::RobotState& panda_state)

rclcpp::Logger getLogger()
{
return moveit::getLogger("moveit_collision_detection_fcl.test.test_fcl_env");
return moveit::getLogger("moveit.core.collision_detection_fcl.test_fcl_env");
}

class CollisionDetectionEnvTest : public testing::Test
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -373,7 +373,8 @@ class PosedBodySphereDecompositionVector
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

PosedBodySphereDecompositionVector() : logger_(moveit::getLogger("posed_body_sphere_decomposition_vector"))
PosedBodySphereDecompositionVector()
: logger_(moveit::getLogger("moveit.core.posed_body_sphere_decomposition_vector"))
{
}

Expand Down Expand Up @@ -447,7 +448,7 @@ class PosedBodyPointDecompositionVector
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

PosedBodyPointDecompositionVector() : logger_(moveit::getLogger("posed_body_point_decomposition_vector"))
PosedBodyPointDecompositionVector() : logger_(moveit::getLogger("moveit.core.posed_body_point_decomposition_vector"))
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_common_distance_field");
return moveit::getLogger("moveit.core.collision_common_distance_field");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("collision_distance_field_types");
return moveit::getLogger("moveit.core.collision_distance_field_types");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(
const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution,
double collision_tolerance, double max_propogation_distance, double /*padding*/, double /*scale*/)
: CollisionEnv(robot_model), logger_(moveit::getLogger("collision_robot_distance_field"))
: CollisionEnv(robot_model), logger_(moveit::getLogger("moveit.core.collision_robot_distance_field"))
{
initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), origin, use_signed_distance_field,
resolution, collision_tolerance, max_propogation_distance);
Expand All @@ -80,7 +80,8 @@ CollisionEnvDistanceField::CollisionEnvDistanceField(
const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution,
double collision_tolerance, double max_propogation_distance, double padding, double scale)
: CollisionEnv(robot_model, world, padding, scale), logger_(moveit::getLogger("collision_robot_distance_field"))
: CollisionEnv(robot_model, world, padding, scale)
, logger_(moveit::getLogger("moveit.core.collision_robot_distance_field"))
{
initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), origin, use_signed_distance_field,
resolution, collision_tolerance, max_propogation_distance);
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/constraint_samplers/src/constraint_sampler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("constraint_sampler");
return moveit::getLogger("moveit.core.constraint_sampler");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("constraint_sampler_manager");
return moveit::getLogger("moveit.core.constraint_sampler_manager");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("constraint_sampler_tools");
return moveit::getLogger("moveit.core.constraint_sampler_tools");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("default_constraint_samplers");
return moveit::getLogger("moveit.core.default_constraint_samplers");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("union_constraint_sampler");
return moveit::getLogger("moveit.core.union_constraint_sampler");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/constraint_samplers/test/pr2_arm_ik.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("moveit_constaint_samplers.test.pr2_arm_ik");
return moveit::getLogger("moveit.core.moveit_constaint_samplers.test.pr2_arm_ik");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("moveit_constraint_samplers.test.pr2_arm_kinematics_plugin");
return moveit::getLogger("moveit.core.moveit_constraint_samplers.test.pr2_arm_kinematics_plugin");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/distance_field/src/distance_field.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("distance_field");
return moveit::getLogger("moveit.core.distance_field");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("propagation_distance_field");
return moveit::getLogger("moveit.core.propagation_distance_field");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/dynamics_solver/src/dynamics_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("dynamics_solver");
return moveit::getLogger("moveit.core.dynamics_solver");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("kinematic_constraints");
return moveit::getLogger("moveit.core.kinematic_constraints");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/kinematic_constraints/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("moveit_kinematic_constraints");
return moveit::getLogger("moveit.core.kinematic_constraints");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,7 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase
}

// Otherwise throw error because this function should have been implemented
RCLCPP_ERROR(moveit::getLogger("kinematics_base"),
RCLCPP_ERROR(moveit::getLogger("moveit.core.kinematics_base"),
"This kinematic solver does not support searchPositionIK with multiple poses");
return false;
}
Expand Down Expand Up @@ -363,7 +363,7 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase
return searchPositionIK(ik_poses, ik_seed_state, timeout, consistency_limits, solution, solution_callback,
error_code, options, context_state);
}
RCLCPP_ERROR(moveit::getLogger("kinematics_base"),
RCLCPP_ERROR(moveit::getLogger("moveit.core.kinematics_base"),
"This kinematic solver does not support IK solution cost functions");
return false;
}
Expand Down Expand Up @@ -437,8 +437,9 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase
{
if (tip_frames_.size() > 1)
{
RCLCPP_ERROR(moveit::getLogger("kinematics_base"), "This kinematic solver has more than one tip frame, "
"do not call getTipFrame()");
RCLCPP_ERROR(moveit::getLogger("moveit.core.kinematics_base"),
"This kinematic solver has more than one tip frame, "
"do not call getTipFrame()");
}

return tip_frames_[0];
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/kinematics_base/src/kinematics_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("kinematics_base");
return moveit::getLogger("moveit.core.kinematics_base");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/kinematics_metrics/src/kinematics_metrics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("kinematics_metrics");
return moveit::getLogger("moveit.core.kinematics_metrics");
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ namespace online_signal_smoothing
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("AccelerationLimitedPlugin");
return moveit::getLogger("moveit.core.acceleration_limited_plugin");
}

// The threshold below which any velocity or position difference is considered zero (rad and rad/s).
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/planning_interface/src/planning_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("planning_interface");
return moveit::getLogger("moveit.core.planning_interface");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/planning_scene/src/planning_scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("planning_scene");
return moveit::getLogger("moveit.core.planning_scene");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/floating_joint_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ constexpr size_t STATE_SPACE_DIMENSION = 7;

rclcpp::Logger getLogger()
{
return moveit::getLogger("floating_joint_model");
return moveit::getLogger("moveit.core.floating_joint_model");
}

} // namespace
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/joint_model_group.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("joint_model_group");
return moveit::getLogger("moveit.core.joint_model_group");
}

// check if a parent or ancestor of joint is included in this group
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_model/src/robot_model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("robot_model");
return moveit::getLogger("moveit.core.robot_model");
}
} // namespace

Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_state/src/cartesian_interpolator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ namespace

rclcpp::Logger getLogger()
{
return moveit::getLogger("cartesian_interpolator");
return moveit::getLogger("moveit.core.cartesian_interpolator");
}

std::optional<int> hasRelativeJointSpaceJump(const std::vector<moveit::core::RobotStatePtr>& waypoints,
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_state/src/conversions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("conversions");
return moveit::getLogger("moveit.core.conversions");
}

bool jointStateToRobotStateImpl(const sensor_msgs::msg::JointState& joint_state, RobotState& state)
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/robot_state/src/robot_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("robot_state");
return moveit::getLogger("moveit.core.robot_state");
}
} // namespace

Expand Down
Loading

0 comments on commit f06f38b

Please sign in to comment.