Skip to content

Commit

Permalink
Switch to std::make_shared.
Browse files Browse the repository at this point in the history
  • Loading branch information
de-vri-es authored and davetcoleman committed Sep 27, 2016
1 parent ec34ae7 commit dad8ddc
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@
#include <moveit/collision_distance_field/collision_world_distance_field.h>
#include <moveit/collision_distance_field/collision_common_distance_field.h>
#include <moveit/distance_field/propagation_distance_field.h>
#include <boost/make_shared.hpp>
#include <boost/bind.hpp>
#include <memory>

namespace collision_detection
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,13 @@
#include <controller_manager_msgs/SwitchController.h>

#include <pluginlib/class_list_macros.h>
#include <map>

#include <pluginlib/class_loader.h>

#include <boost/bimap.hpp>

#include <map>
#include <memory>

namespace moveit_ros_control_interface
{
/**
Expand Down Expand Up @@ -401,7 +402,7 @@ class MoveItMultiControllerManager : public moveit_controller_manager::MoveItCon
{ // create MoveItControllerManager if it does not exists
ROS_INFO_STREAM("Adding controller_manager interface for node at namespace " << ns);
controller_managers_.insert(
std::make_pair(ns, boost::make_shared<moveit_ros_control_interface::MoveItControllerManager>(ns)));
std::make_pair(ns, std::make_shared<moveit_ros_control_interface::MoveItControllerManager>(ns)));
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#include <ros/ros.h>
#include <moveit_ros_control_interface/ControllerHandle.h>
#include <pluginlib/class_list_macros.h>
#include <boost/shared_ptr.hpp>
#include <moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h>
#include <memory>

namespace moveit_ros_control_interface
{
Expand All @@ -51,7 +51,7 @@ class JointTrajectoryControllerAllocator : public ControllerHandleAllocator
virtual moveit_controller_manager::MoveItControllerHandlePtr alloc(const std::string &name,
const std::vector<std::string> &resources)
{
return boost::make_shared<moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle>(
return std::make_shared<moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle>(
name, "follow_joint_trajectory");
}
};
Expand Down

0 comments on commit dad8ddc

Please sign in to comment.