Skip to content

Commit

Permalink
Use boost::make_shared instead of new for constructing boost::shared_…
Browse files Browse the repository at this point in the history
…ptr (#740)
  • Loading branch information
kartikmohta authored and dirk-thomas committed Mar 1, 2016
1 parent 8e24f23 commit 90b0eb7
Show file tree
Hide file tree
Showing 50 changed files with 218 additions and 217 deletions.
6 changes: 3 additions & 3 deletions clients/roscpp/include/ros/advertise_service_options.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ struct ROSCPP_DECL AdvertiseServiceOptions
datatype = st::datatype<MReq>();
req_datatype = mt::datatype<MReq>();
res_datatype = mt::datatype<MRes>();
helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<ServiceSpec<MReq, MRes> >(_callback));
helper = boost::make_shared<ServiceCallbackHelperT<ServiceSpec<MReq, MRes> > >(_callback);
}

/**
Expand All @@ -92,7 +92,7 @@ struct ROSCPP_DECL AdvertiseServiceOptions
datatype = st::datatype<Service>();
req_datatype = mt::datatype<Request>();
res_datatype = mt::datatype<Response>();
helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<ServiceSpec<Request, Response> >(_callback));
helper = boost::make_shared<ServiceCallbackHelperT<ServiceSpec<Request, Response> > >(_callback);
}

/**
Expand All @@ -112,7 +112,7 @@ struct ROSCPP_DECL AdvertiseServiceOptions
datatype = st::datatype<Request>();
req_datatype = mt::datatype<Request>();
res_datatype = mt::datatype<Response>();
helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<Spec>(_callback));
helper = boost::make_shared<ServiceCallbackHelperT<Spec> >(_callback);
}

std::string service; ///< Service name
Expand Down
1 change: 1 addition & 0 deletions clients/roscpp/include/ros/forwards.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#include <list>

#include <boost/shared_ptr.hpp>
#include <boost/make_shared.hpp>
#include <boost/weak_ptr.hpp>
#include <boost/function.hpp>

Expand Down
16 changes: 8 additions & 8 deletions clients/roscpp/include/ros/node_handle.h
Original file line number Diff line number Diff line change
Expand Up @@ -387,7 +387,7 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_objec
\verbatim
ros::NodeHandle nodeHandle;
void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
boost::shared_ptr<Foo> foo_object(new Foo);
boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
if (sub) // Enter if subscriber is valid
{
Expand Down Expand Up @@ -450,7 +450,7 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_objec
\verbatim
ros::NodeHandle nodeHandle;
void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
boost::shared_ptr<Foo> foo_object(new Foo);
boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
if (sub) // Enter if subscriber is valid
{
Expand Down Expand Up @@ -496,7 +496,7 @@ void Foo::callback(const std_msgs::Empty::ConstPtr& message)
{
}
boost::shared_ptr<Foo> foo_object(new Foo);
boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object);
\endverbatim
*
Expand All @@ -514,7 +514,7 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object
\verbatim
ros::NodeHandle nodeHandle;
void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
boost::shared_ptr<Foo> foo_object(new Foo);
boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
if (sub) // Enter if subscriber is valid
{
Expand Down Expand Up @@ -561,7 +561,7 @@ void Foo::callback(const std_msgs::Empty::ConstPtr& message)
{
}
boost::shared_ptr<Foo> foo_object(new Foo);
boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object);
\endverbatim
*
Expand All @@ -579,7 +579,7 @@ ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object
\verbatim
ros::NodeHandle nodeHandle;
void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
boost::shared_ptr<Foo> foo_object(new Foo);
boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
if (sub) // Enter if subscriber is valid
{
Expand Down Expand Up @@ -940,7 +940,7 @@ bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
return true;
}
boost::shared_ptr<Foo> foo_object(new Foo);
boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, foo_object);
\endverbatim
*
Expand Down Expand Up @@ -987,7 +987,7 @@ bool Foo::callback(ros::ServiceEvent<std_srvs::Empty, std_srvs::Empty>& event)
return true;
}
boost::shared_ptr<Foo> foo_object(new Foo);
boost::shared_ptr<Foo> foo_object(boost::make_shared<Foo>());
ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, foo_object);
\endverbatim
*
Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/include/ros/service_callback_helper.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ struct ROSCPP_DECL ServiceCallbackHelperCallParams
template<typename M>
inline boost::shared_ptr<M> defaultServiceCreateFunction()
{
return boost::shared_ptr<M>(new M);
return boost::make_shared<M>();
}

template<typename MReq, typename MRes>
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/include/ros/subscribe_options.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ struct ROSCPP_DECL SubscribeOptions
queue_size = _queue_size;
md5sum = message_traits::md5sum<MessageType>();
datatype = message_traits::datatype<MessageType>();
helper = SubscriptionCallbackHelperPtr(new SubscriptionCallbackHelperT<P>(_callback, factory_fn));
helper = boost::make_shared<SubscriptionCallbackHelperT<P> >(_callback, factory_fn);
}

/**
Expand All @@ -109,7 +109,7 @@ struct ROSCPP_DECL SubscribeOptions
queue_size = _queue_size;
md5sum = message_traits::md5sum<MessageType>();
datatype = message_traits::datatype<MessageType>();
helper = SubscriptionCallbackHelperPtr(new SubscriptionCallbackHelperT<const boost::shared_ptr<MessageType const>&>(_callback, factory_fn));
helper = boost::make_shared<SubscriptionCallbackHelperT<const boost::shared_ptr<MessageType const>&> >(_callback, factory_fn);
}

std::string topic; ///< Topic to subscribe to
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/include/ros/timer_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -282,7 +282,7 @@ template<class T, class D, class E>
int32_t TimerManager<T, D, E>::add(const D& period, const boost::function<void(const E&)>& callback, CallbackQueueInterface* callback_queue,
const VoidConstPtr& tracked_object, bool oneshot)
{
TimerInfoPtr info(new TimerInfo);
TimerInfoPtr info(boost::make_shared<TimerInfo>());
info->period = period;
info->callback = callback;
info->callback_queue = callback_queue;
Expand Down Expand Up @@ -515,7 +515,7 @@ void TimerManager<T, D, E>::threadFunc()
current = T::now();

//ROS_DEBUG("Scheduling timer callback for timer [%d] of period [%f], [%f] off expected", info->handle, info->period.toSec(), (current - info->next_expected).toSec());
CallbackInterfacePtr cb(new TimerQueueCallback(this, info, info->last_expected, info->last_real, info->next_expected));
CallbackInterfacePtr cb(boost::make_shared<TimerQueueCallback>(this, info, info->last_expected, info->last_real, info->next_expected));
info->callback_queue->addCallback(cb, (uint64_t)info.get());

waiting_.pop_front();
Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/src/libros/callback_queue.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ void CallbackQueue::addCallback(const CallbackInterfacePtr& callback, uint64_t r
M_IDInfo::iterator it = id_info_.find(removal_id);
if (it == id_info_.end())
{
IDInfoPtr id_info(new IDInfo);
IDInfoPtr id_info(boost::make_shared<IDInfo>());
id_info->id = removal_id;
id_info_.insert(std::make_pair(removal_id, id_info));
}
Expand Down
14 changes: 7 additions & 7 deletions clients/roscpp/src/libros/connection_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ const ConnectionManagerPtr& ConnectionManager::instance()
boost::mutex::scoped_lock lock(g_connection_manager_mutex);
if (!g_connection_manager)
{
g_connection_manager.reset(new ConnectionManager);
g_connection_manager = boost::make_shared<ConnectionManager>();
}
}

Expand All @@ -73,7 +73,7 @@ void ConnectionManager::start()
this));

// Bring up the TCP listener socket
tcpserver_transport_ = TransportTCPPtr(new TransportTCP(&poll_manager_->getPollSet()));
tcpserver_transport_ = boost::make_shared<TransportTCP>(&poll_manager_->getPollSet());
if (!tcpserver_transport_->listen(network::getTCPROSPort(),
MAX_TCPROS_CONN_QUEUE,
boost::bind(&ConnectionManager::tcprosAcceptConnection, this, _1)))
Expand All @@ -83,7 +83,7 @@ void ConnectionManager::start()
}

// Bring up the UDP listener socket
udpserver_transport_ = TransportUDPPtr(new TransportUDP(&poll_manager_->getPollSet()));
udpserver_transport_ = boost::make_shared<TransportUDP>(&poll_manager_->getPollSet());
if (!udpserver_transport_->createIncoming(0, true))
{
ROS_FATAL("Listen failed");
Expand Down Expand Up @@ -185,7 +185,7 @@ void ConnectionManager::udprosIncomingConnection(const TransportUDPPtr& transpor
std::string client_uri = ""; // TODO: transport->getClientURI();
ROSCPP_LOG_DEBUG("UDPROS received a connection from [%s]", client_uri.c_str());

ConnectionPtr conn(new Connection());
ConnectionPtr conn(boost::make_shared<Connection>());
addConnection(conn);

conn->initialize(transport, true, NULL);
Expand All @@ -197,7 +197,7 @@ void ConnectionManager::tcprosAcceptConnection(const TransportTCPPtr& transport)
std::string client_uri = transport->getClientURI();
ROSCPP_LOG_DEBUG("TCPROS received a connection from [%s]", client_uri.c_str());

ConnectionPtr conn(new Connection());
ConnectionPtr conn(boost::make_shared<Connection>());
addConnection(conn);

conn->initialize(transport, true, boost::bind(&ConnectionManager::onConnectionHeaderReceived, this, _1, _2));
Expand All @@ -212,7 +212,7 @@ bool ConnectionManager::onConnectionHeaderReceived(const ConnectionPtr& conn, co
ROSCPP_LOG_DEBUG("Connection: Creating TransportSubscriberLink for topic [%s] connected to [%s]",
val.c_str(), conn->getRemoteString().c_str());

TransportSubscriberLinkPtr sub_link(new TransportSubscriberLink());
TransportSubscriberLinkPtr sub_link(boost::make_shared<TransportSubscriberLink>());
sub_link->initialize(conn);
ret = sub_link->handleHeader(header);
}
Expand All @@ -221,7 +221,7 @@ bool ConnectionManager::onConnectionHeaderReceived(const ConnectionPtr& conn, co
ROSCPP_LOG_DEBUG("Connection: Creating ServiceClientLink for service [%s] connected to [%s]",
val.c_str(), conn->getRemoteString().c_str());

ServiceClientLinkPtr link(new ServiceClientLink());
ServiceClientLinkPtr link(boost::make_shared<ServiceClientLink>());
link->initialize(conn);
ret = link->handleHeader(header);
}
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/src/libros/node_handle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,8 +295,8 @@ Publisher NodeHandle::advertise(AdvertiseOptions& ops)
}
}

SubscriberCallbacksPtr callbacks(new SubscriberCallbacks(ops.connect_cb, ops.disconnect_cb,
ops.tracked_object, ops.callback_queue));
SubscriberCallbacksPtr callbacks(boost::make_shared<SubscriberCallbacks>(ops.connect_cb, ops.disconnect_cb,
ops.tracked_object, ops.callback_queue));

if (TopicManager::instance()->advertise(ops, callbacks))
{
Expand Down
6 changes: 3 additions & 3 deletions clients/roscpp/src/libros/publication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ void Publication::addCallbacks(const SubscriberCallbacksPtr& callbacks)
for (; it != end; ++it)
{
const SubscriberLinkPtr& sub_link = *it;
CallbackInterfacePtr cb(new PeerConnDisconnCallback(callbacks->connect_, sub_link, callbacks->has_tracked_object_, callbacks->tracked_object_));
CallbackInterfacePtr cb(boost::make_shared<PeerConnDisconnCallback>(callbacks->connect_, sub_link, callbacks->has_tracked_object_, callbacks->tracked_object_));
callbacks->callback_queue_->addCallback(cb, (uint64_t)callbacks.get());
}
}
Expand Down Expand Up @@ -331,7 +331,7 @@ void Publication::peerConnect(const SubscriberLinkPtr& sub_link)
const SubscriberCallbacksPtr& cbs = *it;
if (cbs->connect_ && cbs->callback_queue_)
{
CallbackInterfacePtr cb(new PeerConnDisconnCallback(cbs->connect_, sub_link, cbs->has_tracked_object_, cbs->tracked_object_));
CallbackInterfacePtr cb(boost::make_shared<PeerConnDisconnCallback>(cbs->connect_, sub_link, cbs->has_tracked_object_, cbs->tracked_object_));
cbs->callback_queue_->addCallback(cb, (uint64_t)cbs.get());
}
}
Expand All @@ -346,7 +346,7 @@ void Publication::peerDisconnect(const SubscriberLinkPtr& sub_link)
const SubscriberCallbacksPtr& cbs = *it;
if (cbs->disconnect_ && cbs->callback_queue_)
{
CallbackInterfacePtr cb(new PeerConnDisconnCallback(cbs->disconnect_, sub_link, cbs->has_tracked_object_, cbs->tracked_object_));
CallbackInterfacePtr cb(boost::make_shared<PeerConnDisconnCallback>(cbs->disconnect_, sub_link, cbs->has_tracked_object_, cbs->tracked_object_));
cbs->callback_queue_->addCallback(cb, (uint64_t)cbs.get());
}
}
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/src/libros/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,12 +57,12 @@ void Publisher::Impl::unadvertise()
}

Publisher::Publisher(const std::string& topic, const std::string& md5sum, const std::string& datatype, const NodeHandle& node_handle, const SubscriberCallbacksPtr& callbacks)
: impl_(new Impl)
: impl_(boost::make_shared<Impl>())
{
impl_->topic_ = topic;
impl_->md5sum_ = md5sum;
impl_->datatype_ = datatype;
impl_->node_handle_ = NodeHandlePtr(new NodeHandle(node_handle));
impl_->node_handle_ = boost::make_shared<NodeHandle>(node_handle);
impl_->callbacks_ = callbacks;
}

Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/src/libros/rosout_appender.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ ROSOutAppender::ROSOutAppender()
AdvertiseOptions ops;
ops.init<rosgraph_msgs::Log>(names::resolve("/rosout"), 0);
ops.latch = true;
SubscriberCallbacksPtr cbs(new SubscriberCallbacks);
SubscriberCallbacksPtr cbs(boost::make_shared<SubscriberCallbacks>());
TopicManager::instance()->advertise(ops, cbs);
}

Expand All @@ -74,7 +74,7 @@ const std::string& ROSOutAppender::getLastError() const

void ROSOutAppender::log(::ros::console::Level level, const char* str, const char* file, const char* function, int line)
{
rosgraph_msgs::LogPtr msg(new rosgraph_msgs::Log);
rosgraph_msgs::LogPtr msg(boost::make_shared<rosgraph_msgs::Log>());

msg->header.stamp = ros::Time::now();
if (level == ros::console::levels::Debug)
Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/src/libros/service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ bool service::exists(const std::string& service_name, bool print_failure_reason)

if (ServiceManager::instance()->lookupService(mapped_name, host, port))
{
TransportTCPPtr transport(new TransportTCP(0, TransportTCP::SYNCHRONOUS));
TransportTCPPtr transport(boost::make_shared<TransportTCP>(static_cast<ros::PollSet*>(NULL), TransportTCP::SYNCHRONOUS));

if (transport->connect(host, port))
{
Expand Down
10 changes: 5 additions & 5 deletions clients/roscpp/src/libros/service_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ const ServiceManagerPtr& ServiceManager::instance()
boost::mutex::scoped_lock lock(g_service_manager_mutex);
if (!g_service_manager)
{
g_service_manager.reset(new ServiceManager);
g_service_manager = boost::make_shared<ServiceManager>();
}
}

Expand Down Expand Up @@ -148,7 +148,7 @@ bool ServiceManager::advertiseService(const AdvertiseServiceOptions& ops)
return false;
}

ServicePublicationPtr pub(new ServicePublication(ops.service, ops.md5sum, ops.datatype, ops.req_datatype, ops.res_datatype, ops.helper, ops.callback_queue, ops.tracked_object));
ServicePublicationPtr pub(boost::make_shared<ServicePublication>(ops.service, ops.md5sum, ops.datatype, ops.req_datatype, ops.res_datatype, ops.helper, ops.callback_queue, ops.tracked_object));
service_publications_.push_back(pub);
}

Expand Down Expand Up @@ -262,17 +262,17 @@ ServiceServerLinkPtr ServiceManager::createServiceServerLink(const std::string&
return ServiceServerLinkPtr();
}

TransportTCPPtr transport(new TransportTCP(&poll_manager_->getPollSet()));
TransportTCPPtr transport(boost::make_shared<TransportTCP>(&poll_manager_->getPollSet()));

// Make sure to initialize the connection *before* transport->connect()
// is called, otherwise we might miss a connect error (see #434).
ConnectionPtr connection(new Connection());
ConnectionPtr connection(boost::make_shared<Connection>());
connection_manager_->addConnection(connection);
connection->initialize(transport, false, HeaderReceivedFunc());

if (transport->connect(serv_host, serv_port))
{
ServiceServerLinkPtr client(new ServiceServerLink(service, persistent, request_md5sum, response_md5sum, header_values));
ServiceServerLinkPtr client(boost::make_shared<ServiceServerLink>(service, persistent, request_md5sum, response_md5sum, header_values));

{
boost::mutex::scoped_lock lock(service_server_links_mutex_);
Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/src/libros/service_publication.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,7 @@ class ServiceCallback : public CallbackInterface

void ServicePublication::processRequest(boost::shared_array<uint8_t> buf, size_t num_bytes, const ServiceClientLinkPtr& link)
{
CallbackInterfacePtr cb(new ServiceCallback(helper_, buf, num_bytes, link, has_tracked_object_, tracked_object_));
CallbackInterfacePtr cb(boost::make_shared<ServiceCallback>(helper_, buf, num_bytes, link, has_tracked_object_, tracked_object_));
callback_queue_->addCallback(cb, (uint64_t)this);
}

Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/src/libros/service_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,10 +56,10 @@ void ServiceServer::Impl::unadvertise()
}

ServiceServer::ServiceServer(const std::string& service, const NodeHandle& node_handle)
: impl_(new Impl)
: impl_(boost::make_shared<Impl>())
{
impl_->service_ = service;
impl_->node_handle_ = NodeHandlePtr(new NodeHandle(node_handle));
impl_->node_handle_ = boost::make_shared<NodeHandle>(node_handle);
}

ServiceServer::ServiceServer(const ServiceServer& rhs)
Expand Down
2 changes: 1 addition & 1 deletion clients/roscpp/src/libros/service_server_link.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -326,7 +326,7 @@ void ServiceServerLink::processNextCall()

bool ServiceServerLink::call(const SerializedMessage& req, SerializedMessage& resp)
{
CallInfoPtr info(new CallInfo);
CallInfoPtr info(boost::make_shared<CallInfo>());
info->req_ = req;
info->resp_ = &resp;
info->success_ = false;
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/src/libros/subscriber.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,10 @@ namespace ros

Subscriber::Subscriber(const std::string& topic, const NodeHandle& node_handle,
const SubscriptionCallbackHelperPtr& helper)
: impl_(new Impl)
: impl_(boost::make_shared<Impl>())
{
impl_->topic_ = topic;
impl_->node_handle_ = NodeHandlePtr(new NodeHandle(node_handle));
impl_->node_handle_ = boost::make_shared<NodeHandle>(node_handle);
impl_->helper_ = helper;
}

Expand Down
Loading

0 comments on commit 90b0eb7

Please sign in to comment.