diff --git a/franka_example_controllers/include/franka_example_controllers/cartesian_impedance_example_controller.h b/franka_example_controllers/include/franka_example_controllers/cartesian_impedance_example_controller.h index 4e02d493d92a6206ac07ca73487de1e1ed165b5c..e4ea62ca8e6bde9ba988540b6289eb794717ab55 100644 --- a/franka_example_controllers/include/franka_example_controllers/cartesian_impedance_example_controller.h +++ b/franka_example_controllers/include/franka_example_controllers/cartesian_impedance_example_controller.h @@ -6,8 +6,6 @@ #include <string> #include <vector> -#include <Eigen/Dense> -#include <boost/scoped_ptr.hpp> #include <controller_interface/multi_interface_controller.h> #include <dynamic_reconfigure/server.h> #include <geometry_msgs/PoseStamped.h> @@ -15,6 +13,7 @@ #include <hardware_interface/robot_hw.h> #include <ros/node_handle.h> #include <ros/time.h> +#include <Eigen/Dense> #include <franka_example_controllers/compliance_paramConfig.h> #include <franka_hw/franka_model_interface.h> @@ -60,7 +59,7 @@ class CartesianImpedanceExampleController : public controller_interface::MultiIn const Eigen::Matrix<double, 7, 1>& gravity); // Dynamic reconfigure - boost::scoped_ptr<dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig>> + std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::compliance_paramConfig>> dynamic_server_compliance_param_; ros::NodeHandle dynamic_reconfigure_compliance_param_node_; void complianceParamCallback(franka_example_controllers::compliance_paramConfig& config, diff --git a/franka_example_controllers/include/franka_example_controllers/force_example_controller.h b/franka_example_controllers/include/franka_example_controllers/force_example_controller.h index ff8cb56d2a60b2ca943a5588203fe6ff1e3160e0..1100ff92745e86ed55d53f4cbd89335c9168fdac 100644 --- a/franka_example_controllers/include/franka_example_controllers/force_example_controller.h +++ b/franka_example_controllers/include/franka_example_controllers/force_example_controller.h @@ -6,8 +6,6 @@ #include <string> #include <vector> -#include <Eigen/Core> -#include <boost/scoped_ptr.hpp> #include <controller_interface/multi_interface_controller.h> #include <dynamic_reconfigure/server.h> #include <franka_hw/franka_model_interface.h> @@ -16,6 +14,7 @@ #include <hardware_interface/robot_hw.h> #include <ros/node_handle.h> #include <ros/time.h> +#include <Eigen/Core> #include <franka_example_controllers/desired_mass_paramConfig.h> @@ -46,8 +45,7 @@ class ForceExampleController : public controller_interface::MultiInterfaceContro Eigen::Matrix<double, 7, 1> tau_error_; // Dynamic reconfigure - boost::scoped_ptr< - dynamic_reconfigure::Server<franka_example_controllers::desired_mass_paramConfig>> + std::unique_ptr<dynamic_reconfigure::Server<franka_example_controllers::desired_mass_paramConfig>> dynamic_server_desired_mass_param_; ros::NodeHandle dynamic_reconfigure_desired_mass_param_node_; void desiredMassParamCallback(franka_example_controllers::desired_mass_paramConfig& config,