Skip to content

Commit

Permalink
Fix more clang warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Jan 8, 2023
1 parent 27e8b65 commit 499c16b
Show file tree
Hide file tree
Showing 2 changed files with 1 addition and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ class HybridPlanningDemo
send_goal_options.feedback_callback =
[](const rclcpp_action::ClientGoalHandle<moveit_msgs::action::HybridPlanner>::SharedPtr& /*unused*/,
const std::shared_ptr<const moveit_msgs::action::HybridPlanner::Feedback>& feedback) {
RCLCPP_INFO(LOGGER, feedback->feedback.c_str());
RCLCPP_INFO_STREAM(LOGGER, feedback->feedback);
};

RCLCPP_INFO(LOGGER, "Sending hybrid planning goal");
Expand Down
2 changes: 0 additions & 2 deletions moveit_ros/moveit_servo/src/servo_calcs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,6 @@ namespace moveit_servo
{
namespace
{
constexpr char CONDITION_TOPIC[] = "~/condition";

static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_servo.servo_calcs");
constexpr auto ROS_LOG_THROTTLE_PERIOD = std::chrono::milliseconds(3000).count();
static constexpr double STOPPED_VELOCITY_EPS = 1e-4; // rad/s
Expand Down

0 comments on commit 499c16b

Please sign in to comment.