Skip to content

Commit

Permalink
apply changes from review
Browse files Browse the repository at this point in the history
Signed-off-by: Tyler Weaver <[email protected]>
  • Loading branch information
tylerjw committed Dec 4, 2023
1 parent c5c7e81 commit 3e3a622
Show file tree
Hide file tree
Showing 18 changed files with 25 additions and 26 deletions.
5 changes: 3 additions & 2 deletions moveit_core/exceptions/src/exceptions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,11 +45,12 @@ namespace moveit

ConstructException::ConstructException(const std::string& what_arg) : std::runtime_error(what_arg)
{
RCLCPP_ERROR(getLogger("exception"), "Error during construction of object: %s\nException thrown.", what_arg.c_str());
RCLCPP_ERROR(getLogger("moveit_exception"), "Error during construction of object: %s\nException thrown.",
what_arg.c_str());
}

Exception::Exception(const std::string& what_arg) : std::runtime_error(what_arg)
{
RCLCPP_ERROR(getLogger("exception"), "%s\nException thrown.", what_arg.c_str());
RCLCPP_ERROR(getLogger("moveit_exception"), "%s\nException thrown.", what_arg.c_str());
}
} // namespace moveit
12 changes: 5 additions & 7 deletions moveit_core/robot_trajectory/test/test_robot_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,6 @@ class RobotTrajectoryTestFixture : public testing::Test

void TearDown() override
{
robot_model_.reset();
robot_state_.reset();
}

void initTestTrajectory(robot_trajectory::RobotTrajectoryPtr& trajectory)
Expand Down Expand Up @@ -339,19 +337,19 @@ class OneRobot : public testing::Test

trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, arm_jmg_name_);

ASSERT_EQ(trajectory->getGroupName(), arm_jmg_name_) << "Generated trajectory group name does not match";
ASSERT_TRUE(trajectory->empty()) << "Generated trajectory not empty";
EXPECT_EQ(trajectory->getGroupName(), arm_jmg_name_) << "Generated trajectory group name does not match";
EXPECT_TRUE(trajectory->empty()) << "Generated trajectory not empty";

double duration_from_previous = 0.1;
std::size_t waypoint_count = 5;
for (std::size_t ix = 0; ix < waypoint_count; ++ix)
trajectory->addSuffixWayPoint(*robot_state_, duration_from_previous);
// Quick check that getDuration is working correctly
ASSERT_EQ(trajectory->getDuration(), duration_from_previous * waypoint_count)
EXPECT_EQ(trajectory->getDuration(), duration_from_previous * waypoint_count)
<< "Generated trajectory duration incorrect";
ASSERT_EQ(waypoint_count, trajectory->getWayPointDurations().size())
EXPECT_EQ(waypoint_count, trajectory->getWayPointDurations().size())
<< "Generated trajectory has the wrong number of waypoints";
ASSERT_EQ(waypoint_count, trajectory->size());
EXPECT_EQ(waypoint_count, trajectory->size());
}

protected:
Expand Down
2 changes: 1 addition & 1 deletion moveit_core/utils/src/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ rclcpp::Logger& getGlobalRootLogger()
// A random number is appended to the name used for the node to make it unique.
// This unique node and logger name is only used if a user does not set a logger
// through the `setNodeLoggerName` method to their node's logger.
auto name = fmt::format("____moveit_{}", rsl::rng()());
auto name = fmt::format("moveit_{}", rsl::rng()());
try
{
static auto* moveit_node = new rclcpp::Node(name);
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/benchmarks/src/BenchmarkExecutor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("BenchmarkExecutor");
return moveit::getLogger("benchmark_executor");
}
} // namespace

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
namespace move_group
{

ApplyPlanningSceneService::ApplyPlanningSceneService() : MoveGroupCapability("ApplyPlanningSceneService")
ApplyPlanningSceneService::ApplyPlanningSceneService() : MoveGroupCapability("apply_planning_scene_service")
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ rclcpp::Logger getLogger()
}
} // namespace

move_group::ClearOctomapService::ClearOctomapService() : MoveGroupCapability("ClearOctomapService")
move_group::ClearOctomapService::ClearOctomapService() : MoveGroupCapability("clear_octomap_service")
{
}

Expand All @@ -63,7 +63,7 @@ void move_group::ClearOctomapService::clearOctomap(const std::shared_ptr<std_srv
const std::shared_ptr<std_srvs::srv::Empty::Response>& /*res*/)
{
if (!context_->planning_scene_monitor_)
RCLCPP_ERROR(getLogger(), "Cannot clear octomap since planning_scene_monitor_ does not exist.");
RCLCPP_ERROR(getLogger(), "Cannot clear octomap since planning scene monitor has not been initialized.");

RCLCPP_INFO(getLogger(), "Clearing octomap...");
context_->planning_scene_monitor_->clearOctomap();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ rclcpp::Logger getLogger()
}
} // namespace

MoveGroupExecuteTrajectoryAction::MoveGroupExecuteTrajectoryAction() : MoveGroupCapability("ExecuteTrajectoryAction")
MoveGroupExecuteTrajectoryAction::MoveGroupExecuteTrajectoryAction() : MoveGroupCapability("execute_trajectory_action")
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

namespace move_group
{
MoveGroupGetPlanningSceneService::MoveGroupGetPlanningSceneService() : MoveGroupCapability("GetPlanningSceneService")
MoveGroupGetPlanningSceneService::MoveGroupGetPlanningSceneService() : MoveGroupCapability("get_planning_scene_service")
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
namespace move_group
{

MoveGroupKinematicsService::MoveGroupKinematicsService() : MoveGroupCapability("KinematicsService")
MoveGroupKinematicsService::MoveGroupKinematicsService() : MoveGroupCapability("kinematics_service")
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ rclcpp::Logger getLogger()
} // namespace

MoveGroupMoveAction::MoveGroupMoveAction()
: MoveGroupCapability("MoveAction"), move_state_(IDLE), preempt_requested_{ false }
: MoveGroupCapability("move_action"), move_state_(IDLE), preempt_requested_{ false }
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ rclcpp::Logger getLogger()
}
} // namespace

MoveGroupPlanService::MoveGroupPlanService() : MoveGroupCapability("MotionPlanService")
MoveGroupPlanService::MoveGroupPlanService() : MoveGroupCapability("motion_plan_service")
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@

namespace move_group
{
MoveGroupQueryPlannersService::MoveGroupQueryPlannersService() : MoveGroupCapability("QueryPlannersService")
MoveGroupQueryPlannersService::MoveGroupQueryPlannersService() : MoveGroupCapability("query_planners_service")
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@

namespace move_group
{
MoveGroupStateValidationService::MoveGroupStateValidationService() : MoveGroupCapability("StateValidationService")
MoveGroupStateValidationService::MoveGroupStateValidationService() : MoveGroupCapability("state_salidation_service")
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@
namespace move_group
{

TfPublisher::TfPublisher() : MoveGroupCapability("TfPublisher")
TfPublisher::TfPublisher() : MoveGroupCapability("tf_publisher")
{
}

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

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

Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/moveit_servo/src/utils/command.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace
{
rclcpp::Logger getLogger()
{
return moveit::getLogger("servo_command");
return moveit::getLogger("servo");
}

/**
Expand Down

0 comments on commit 3e3a622

Please sign in to comment.