Skip to content

Commit

Permalink
Minor moveit_servo header cleanup (moveit#2173)
Browse files Browse the repository at this point in the history
  • Loading branch information
AndyZe authored and tylerjw committed Jul 1, 2020
1 parent 59b327b commit 158ae30
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,6 @@

#pragma once

#include <mutex>

#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <sensor_msgs/JointState.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down
6 changes: 1 addition & 5 deletions moveit_ros/moveit_servo/include/moveit_servo/servo_calcs.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,6 @@

#pragma once

// System
#include <mutex>

// ROS
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
Expand Down Expand Up @@ -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);

Expand Down

0 comments on commit 158ae30

Please sign in to comment.