diff --git a/effort_controllers/CMakeLists.txt b/effort_controllers/CMakeLists.txt
index af49077c8..ec8e6943a 100644
--- a/effort_controllers/CMakeLists.txt
+++ b/effort_controllers/CMakeLists.txt
@@ -30,6 +30,7 @@ add_library(${PROJECT_NAME}
src/joint_effort_controller.cpp
src/joint_velocity_controller.cpp
src/joint_position_controller.cpp
+ src/joint_group_effort_controller.cpp
)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
diff --git a/effort_controllers/effort_controllers_plugins.xml b/effort_controllers/effort_controllers_plugins.xml
index 1fb8984cc..fca7d1f04 100644
--- a/effort_controllers/effort_controllers_plugins.xml
+++ b/effort_controllers/effort_controllers_plugins.xml
@@ -18,4 +18,10 @@
+
+
+ The JointGroupEffortController tracks effort commands for a set of joints. It expects a EffortJointInterface type of hardware interface.
+
+
+
diff --git a/effort_controllers/include/effort_controllers/joint_group_effort_controller.h b/effort_controllers/include/effort_controllers/joint_group_effort_controller.h
new file mode 100644
index 000000000..36b93babd
--- /dev/null
+++ b/effort_controllers/include/effort_controllers/joint_group_effort_controller.h
@@ -0,0 +1,63 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * Copyright (c) 2012, hiDOF, Inc.
+ * Copyright (c) 2013, PAL Robotics, S.L.
+ * Copyright (c) 2014, Fraunhofer IPA
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+#ifndef EFFORT_CONTROLLERS_JOINT_GROUP_EFFORT_CONTROLLER_H
+#define EFFORT_CONTROLLERS_JOINT_GROUP_EFFORT_CONTROLLER_H
+
+#include
+
+namespace effort_controllers
+{
+
+/**
+ * \brief Forward command controller for a set of effort controlled joints (torque or force).
+ *
+ * This class forwards the commanded efforts down to a set of joints.
+ *
+ * \section ROS interface
+ *
+ * \param type Must be "JointGroupEffortController".
+ * \param joints List of names of the joints to control.
+ *
+ * Subscribes to:
+ * - \b command (std_msgs::Float64MultiArray) : The joint efforts to apply
+ */
+typedef forward_command_controller::ForwardJointGroupCommandController
+ JointGroupEffortController;
+}
+
+#endif
diff --git a/effort_controllers/src/joint_group_effort_controller.cpp b/effort_controllers/src/joint_group_effort_controller.cpp
new file mode 100644
index 000000000..3f9dfd69c
--- /dev/null
+++ b/effort_controllers/src/joint_group_effort_controller.cpp
@@ -0,0 +1,41 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * Copyright (c) 2012, hiDOF, Inc.
+ * Copyright (c) 2013, PAL Robotics, S.L.
+ * Copyright (c) 2014, Fraunhofer IPA
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+#include
+#include
+
+PLUGINLIB_EXPORT_CLASS(effort_controllers::JointGroupEffortController,controller_interface::ControllerBase)
diff --git a/forward_command_controller/include/forward_command_controller/forward_joint_group_command_controller.h b/forward_command_controller/include/forward_command_controller/forward_joint_group_command_controller.h
new file mode 100644
index 000000000..fae88fe77
--- /dev/null
+++ b/forward_command_controller/include/forward_command_controller/forward_joint_group_command_controller.h
@@ -0,0 +1,134 @@
+
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * Copyright (c) 2012, hiDOF, Inc.
+ * Copyright (c) 2013, PAL Robotics, S.L.
+ * Copyright (c) 2014, Fraunhofer IPA
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+#ifndef FORWARD_COMMAND_CONTROLLER_FORWARD_JOINT_GROUP_COMMAND_CONTROLLER_H
+#define FORWARD_COMMAND_CONTROLLER_FORWARD_JOINT_GROUP_COMMAND_CONTROLLER_H
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+
+
+namespace forward_command_controller
+{
+
+/**
+ * \brief Forward command controller for a set of joints.
+ *
+ * This class forwards the command signal down to a set of joints.
+ * Command signal and joint hardware interface are of the same type, e.g. effort commands for an effort-controlled
+ * joint.
+ *
+ * \tparam T Type implementing the JointCommandInterface.
+ *
+ * \section ROS interface
+ *
+ * \param type hardware interface type.
+ * \param joints Names of the joints to control.
+ *
+ * Subscribes to:
+ * - \b command (std_msgs::Float64MultiArray) : The joint commands to apply.
+ */
+template
+class ForwardJointGroupCommandController: public controller_interface::Controller
+{
+public:
+ ForwardJointGroupCommandController() { commands_.clear(); }
+ ~ForwardJointGroupCommandController() {sub_command_.shutdown();}
+
+ bool init(T* hw, ros::NodeHandle &n)
+ {
+ // List of controlled joints
+ std::string param_name = "joints";
+ if(!n.getParam(param_name, joint_names_))
+ {
+ ROS_ERROR_STREAM("Failed to getParam '" << param_name << "' (namespace: " << n.getNamespace() << ").");
+ return false;
+ }
+ n_joints_ = joint_names_.size();
+
+ for(unsigned int i=0; igetHandle(joint_names_[i]));
+ }
+ catch (const hardware_interface::HardwareInterfaceException& e)
+ {
+ ROS_ERROR_STREAM("Exception thrown: " << e.what());
+ return false;
+ }
+ }
+
+ sub_command_ = n.subscribe("command", 1, &ForwardJointGroupCommandController::commandCB, this);
+ return true;
+ }
+
+ void starting(const ros::Time& time) {commands_.resize(n_joints_, 0.0);}
+ void update(const ros::Time& time, const ros::Duration& period)
+ {
+ for(unsigned int i=0; i joint_names_;
+ std::vector< hardware_interface::JointHandle > joints_;
+ std::vector< double > commands_;
+ unsigned int n_joints_;
+
+private:
+ ros::Subscriber sub_command_;
+ void commandCB(const std_msgs::Float64MultiArrayConstPtr& msg)
+ {
+ if(msg->data.size()!=n_joints_)
+ {
+ ROS_ERROR_STREAM("Dimension of command (" << msg->data.size() << ") does not match number of joints (" << n_joints_ << ")! Not executing!");
+ return;
+ }
+ for(unsigned int i=0; idata[i]; }
+ }
+};
+
+}
+
+#endif
diff --git a/position_controllers/CMakeLists.txt b/position_controllers/CMakeLists.txt
index 9553d6cf2..0fbf58ae1 100644
--- a/position_controllers/CMakeLists.txt
+++ b/position_controllers/CMakeLists.txt
@@ -6,7 +6,9 @@ find_package(catkin REQUIRED COMPONENTS controller_interface forward_command_con
include_directories(include ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS})
add_library(${PROJECT_NAME}
- src/joint_position_controller.cpp include/position_controllers/joint_position_controller.h)
+ src/joint_position_controller.cpp
+ src/joint_group_position_controller.cpp
+)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
# Declare catkin project
diff --git a/position_controllers/include/position_controllers/joint_group_position_controller.h b/position_controllers/include/position_controllers/joint_group_position_controller.h
new file mode 100644
index 000000000..30f02136f
--- /dev/null
+++ b/position_controllers/include/position_controllers/joint_group_position_controller.h
@@ -0,0 +1,63 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * Copyright (c) 2012, hiDOF, Inc.
+ * Copyright (c) 2013, PAL Robotics, S.L.
+ * Copyright (c) 2014, Fraunhofer IPA
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+#ifndef POSITION_CONTROLLERS_JOINT_GROUP_POSITION_CONTROLLER_H
+#define POSITION_CONTROLLERS_JOINT_GROUP_POSITION_CONTROLLER_H
+
+#include
+
+namespace position_controllers
+{
+
+/**
+ * \brief Forward command controller for a set of position controlled joints (linear or angular).
+ *
+ * This class forwards the commanded positions down to a set of joints.
+ *
+ * \section ROS interface
+ *
+ * \param type Must be "JointGroupPositionController".
+ * \param joints List of names of the joints to control.
+ *
+ * Subscribes to:
+ * - \b command (std_msgs::Float64MultiArray) : The joint positions to apply
+ */
+typedef forward_command_controller::ForwardJointGroupCommandController
+ JointGroupPositionController;
+}
+
+#endif
diff --git a/position_controllers/position_controllers_plugins.xml b/position_controllers/position_controllers_plugins.xml
index 5d1de5698..05433084a 100644
--- a/position_controllers/position_controllers_plugins.xml
+++ b/position_controllers/position_controllers_plugins.xml
@@ -6,4 +6,10 @@
+
+
+ The JointGroupPositionController tracks position commands for a set of joints. It expects a PositionJointInterface type of hardware interface.
+
+
+
diff --git a/position_controllers/src/joint_group_position_controller.cpp b/position_controllers/src/joint_group_position_controller.cpp
new file mode 100644
index 000000000..f1026a41a
--- /dev/null
+++ b/position_controllers/src/joint_group_position_controller.cpp
@@ -0,0 +1,41 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * Copyright (c) 2012, hiDOF, Inc.
+ * Copyright (c) 2013, PAL Robotics, S.L.
+ * Copyright (c) 2014, Fraunhofer IPA
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+#include
+#include
+
+PLUGINLIB_EXPORT_CLASS(position_controllers::JointGroupPositionController,controller_interface::ControllerBase)
diff --git a/velocity_controllers/CMakeLists.txt b/velocity_controllers/CMakeLists.txt
index 486aeb37c..ebeef5a96 100644
--- a/velocity_controllers/CMakeLists.txt
+++ b/velocity_controllers/CMakeLists.txt
@@ -25,6 +25,7 @@ include_directories(include ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS})
add_library(${PROJECT_NAME}
src/joint_velocity_controller.cpp
src/joint_position_controller.cpp
+ src/joint_group_velocity_controller.cpp
)
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})
diff --git a/velocity_controllers/include/velocity_controllers/joint_group_velocity_controller.h b/velocity_controllers/include/velocity_controllers/joint_group_velocity_controller.h
new file mode 100644
index 000000000..6b6167e6d
--- /dev/null
+++ b/velocity_controllers/include/velocity_controllers/joint_group_velocity_controller.h
@@ -0,0 +1,64 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * Copyright (c) 2012, hiDOF, Inc.
+ * Copyright (c) 2013, PAL Robotics, S.L.
+ * Copyright (c) 2014, Fraunhofer IPA
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+#ifndef VELOCITY_CONTROLLERS_JOINT_GROUP_VELOCITY_CONTROLLER_H
+#define VELOCITY_CONTROLLERS_JOINT_GROUP_VELOCITY_CONTROLLER_H
+
+#include
+
+namespace velocity_controllers
+{
+
+/**
+ * \brief Forward command controller for a set of velocity controlled joints (linear or angular).
+ *
+ * This class forwards the commanded velocities down to a set of joints.
+ *
+ * \section ROS interface
+ *
+ * \param type Must be "JointGroupVelocityController".
+ * \param joints List of names of the joints to control.
+ *
+ * Subscribes to:
+ * - \b command (std_msgs::Float64MultiArray) : The joint velocities to apply
+ */
+typedef forward_command_controller::ForwardJointGroupCommandController
+ JointGroupVelocityController;
+
+}
+
+#endif
diff --git a/velocity_controllers/src/joint_group_velocity_controller.cpp b/velocity_controllers/src/joint_group_velocity_controller.cpp
new file mode 100644
index 000000000..e69042154
--- /dev/null
+++ b/velocity_controllers/src/joint_group_velocity_controller.cpp
@@ -0,0 +1,41 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * Copyright (c) 2012, hiDOF, Inc.
+ * Copyright (c) 2013, PAL Robotics, S.L.
+ * Copyright (c) 2014, Fraunhofer IPA
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * * Redistributions in binary form must reproduce the above
+ * copyright notice, this list of conditions and the following
+ * disclaimer in the documentation and/or other materials provided
+ * with the distribution.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *********************************************************************/
+
+#include
+#include
+
+PLUGINLIB_EXPORT_CLASS(velocity_controllers::JointGroupVelocityController,controller_interface::ControllerBase)
diff --git a/velocity_controllers/velocity_controllers_plugins.xml b/velocity_controllers/velocity_controllers_plugins.xml
index fed678f36..994e30f49 100644
--- a/velocity_controllers/velocity_controllers_plugins.xml
+++ b/velocity_controllers/velocity_controllers_plugins.xml
@@ -12,4 +12,10 @@
+
+
+ The JointGroupVelocityController tracks velocity commands for a set of joints. It expects a VelocityJointInterface type of hardware interface.
+
+
+