From 158ae30a7428a39d41e9deef2a9c79b1f763ad08 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Wed, 1 Jul 2020 07:41:23 -0500 Subject: [PATCH] Minor moveit_servo header cleanup (#2173) --- .../moveit_servo/include/moveit_servo/collision_check.h | 2 -- .../include/moveit_servo/joint_state_subscriber.h | 3 +-- moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h | 6 +----- 3 files changed, 2 insertions(+), 9 deletions(-) diff --git a/moveit_ros/moveit_servo/include/moveit_servo/collision_check.h b/moveit_ros/moveit_servo/include/moveit_servo/collision_check.h index 845b5dac84..6b9610d6ce 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/collision_check.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/collision_check.h @@ -38,8 +38,6 @@ #pragma once -#include - #include #include #include diff --git a/moveit_ros/moveit_servo/include/moveit_servo/joint_state_subscriber.h b/moveit_ros/moveit_servo/include/moveit_servo/joint_state_subscriber.h index 48d362123a..8300134bab 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/joint_state_subscriber.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/joint_state_subscriber.h @@ -50,8 +50,7 @@ namespace moveit_servo class JointStateSubscriber { public: - /** \brief Constructor - */ + /** \brief Constructor */ JointStateSubscriber(ros::NodeHandle& nh, const std::string& joint_state_topic_name); /** \brief Get the latest joint state message */ diff --git a/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h b/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h index 569216238c..a8f676033a 100644 --- a/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h +++ b/moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h @@ -38,9 +38,6 @@ #pragma once -// System -#include - // ROS #include #include @@ -185,8 +182,7 @@ class ServoCalcs bool changeDriftDimensions(moveit_msgs::ChangeDriftDimensions::Request& req, moveit_msgs::ChangeDriftDimensions::Response& res); - /** \brief Start the main calculation timer */ - // Service callback for changing servoing dimensions + /** \brief Service callback for changing servoing dimensions (e.g. ignore rotation about X) */ bool changeControlDimensions(moveit_msgs::ChangeControlDimensions::Request& req, moveit_msgs::ChangeControlDimensions::Response& res);