Skip to content

Commit 6ba0c1e

Browse files
authored
Merge pull request #242 from pazeshun/fix-indigo-kinetic-build
[Depends on #239] Fix indigo & kinetic build
2 parents 7389a49 + 11de69e commit 6ba0c1e

File tree

11 files changed

+121
-62
lines changed

11 files changed

+121
-62
lines changed

.travis.yml

Lines changed: 32 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -5,33 +5,44 @@ python:
55
- "2.7"
66
compiler:
77
- gcc
8+
cache:
9+
apt: true
10+
pip: true
11+
directories:
12+
- $HOME/.ccache
13+
- $HOME/.cache/pip
14+
- $HOME/apt-cacher-ng
15+
dist: trusty
16+
services:
17+
- docker
818
env:
9-
#- ROS_DISTRO=groovy ROSWS=rosws BUILDER=rosbuild USE_DEB=true
10-
#- ROS_DISTRO=groovy ROSWS=rosws BUILDER=rosbuild USE_DEB=false
11-
#- ROS_DISTRO=groovy ROSWS=wstool BUILDER=catkin USE_DEB=true
12-
#- ROS_DISTRO=groovy ROSWS=wstool BUILDER=catkin USE_DEB=false
13-
- ROS_DISTRO=hydro ROSWS=wstool BUILDER=catkin USE_DEB=true USE_JENKINS="true"
14-
- ROS_DISTRO=hydro ROSWS=wstool BUILDER=catkin USE_DEB=false USE_JENKINS="true"
15-
#- ROS_DISTRO=indigo ROSWS=wstool BUILDER=catkin USE_DEB=true
16-
#- ROS_DISTRO=indigo ROSWS=wstool BUILDER=catkin USE_DEB=false
19+
global:
20+
- USE_DOCKER=true
21+
- USE_TRAVIS=true
22+
- ROS_PARALLEL_JOBS="-j1 -l1"
23+
matrix:
24+
#- ROS_DISTRO=groovy ROSWS=rosws BUILDER=rosbuild USE_DEB=true
25+
#- ROS_DISTRO=groovy ROSWS=rosws BUILDER=rosbuild USE_DEB=false
26+
#- ROS_DISTRO=groovy ROSWS=wstool BUILDER=catkin USE_DEB=true
27+
#- ROS_DISTRO=groovy ROSWS=wstool BUILDER=catkin USE_DEB=false
28+
- ROS_DISTRO=hydro ROSWS=wstool BUILDER=catkin USE_DEB=true
29+
- ROS_DISTRO=hydro ROSWS=wstool BUILDER=catkin USE_DEB=false
30+
- ROS_DISTRO=indigo ROSWS=wstool BUILDER=catkin USE_DEB=true
31+
- ROS_DISTRO=indigo ROSWS=wstool BUILDER=catkin USE_DEB=false
32+
- ROS_DISTRO=kinetic ROSWS=wstool BUILDER=catkin USE_DEB=true
33+
- ROS_DISTRO=kinetic ROSWS=wstool BUILDER=catkin USE_DEB=false
1734
matrix:
1835
allow_failures:
19-
- env: ROS_DISTRO=indigo ROSWS=wstool BUILDER=catkin USE_DEB=true
20-
- env: ROS_DISTRO=indigo ROSWS=wstool BUILDER=catkin USE_DEB=false
21-
- env: ROS_DISTRO=hydro ROSWS=wstool BUILDER=catkin USE_DEB=false USE_JENKINS="true"
36+
- env: ROS_DISTRO=hydro ROSWS=wstool BUILDER=catkin USE_DEB=false
37+
- env: ROS_DISTRO=indigo ROSWS=wstool BUILDER=catkin USE_DEB=false
38+
- env: ROS_DISTRO=kinetic ROSWS=wstool BUILDER=catkin USE_DEB=false
2239
before_install:
23-
# add osrf
24-
- sudo sh -c 'echo "deb http://packages.ros.org/ros-shadow-fixed/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/ros-latest.list'
25-
- sudo sh -c 'echo "deb http://packages.osrfoundation.org/drc/ubuntu precise main" > /etc/apt/sources.list.d/drc-latest.list'
26-
- wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
27-
- wget http://packages.osrfoundation.org/drc.key -O - | sudo apt-key add -
40+
# Install openrtm_aist & add osrf
41+
- export BEFORE_SCRIPT="sudo apt-get install -qq -y ros-${ROS_DISTRO}-openrtm-aist; sudo -E sh -c 'echo \"deb http://packages.osrfoundation.org/gazebo/ubuntu-stable \`lsb_release -cs\` main\" > /etc/apt/sources.list.d/gazebo-latest.list'; wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -; sudo apt-get update -qq"
42+
# On kinetic, drcsim is not released
43+
- if [ ${ROS_DISTRO} != "kinetic" ] ; then export BEFORE_SCRIPT="${BEFORE_SCRIPT}; sudo apt-get install -qq -y drcsim"; fi
2844
- if [ $USE_DEB == true ] ; then mkdir -p ~/ros/ws_rtmros_gazebo/src; fi
2945
- if [ $USE_DEB == true ] ; then git clone https://github.com/start-jsk/rtmros_tutorials ~/ros/ws_rtmros_gazebo/src/rtmros_tutorials; fi
30-
install:
31-
- sudo apt-get update -qq
32-
- sudo apt-get install -qq drcsim-hydro
33-
- sudo apt-get install -qq ros-hydro-openrtm-aist
34-
- export ROS_PARALLEL_JOBS="-j1 -l1"
3546
script: source .travis/travis.sh
3647
notifications:
3748
email:

hrpsys_gazebo_atlas/iob/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ set_target_properties(RobotHardware_atlas PROPERTIES LIBRARY_OUTPUT_DIRECTORY ${
2121
set_target_properties(RobotHardware_atlas PROPERTIES OUTPUT_NAME RobotHardware)
2222

2323
add_executable(RobotHardwareComp_atlas ${ROBOTHARDWARE_SOURCE}/RobotHardwareComp.cpp ${comp_source})
24-
target_link_libraries(RobotHardwareComp_atlas ${libs} ${omniorb_LIBRARIES} ${omnidynamic_LIBRARIES} RTC coil)
24+
target_link_libraries(RobotHardwareComp_atlas ${libs} ${omniorb_LIBRARIES} ${omnidynamic_LIBRARIES} RTC coil dl pthread)
2525
set_target_properties(RobotHardwareComp_atlas PROPERTIES OUTPUT_NAME RobotHardwareComp)
2626

2727
install(TARGETS RobotHardwareComp_atlas RobotHardware_atlas hrpIo_atlas

hrpsys_gazebo_atlas/iob/iob.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
#include <cstdlib>
55
#include <cstring>
66
#include <vector>
7-
#include "io/iob.h"
7+
#include "hrpsys/io/iob.h"
88

99
#include <ros/ros.h>
1010
#include <boost/algorithm/string.hpp>

hrpsys_gazebo_general/CMakeLists.txt

Lines changed: 13 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -18,16 +18,25 @@ if(NOT CMAKE_BUILD_TYPE)
1818
FORCE)
1919
endif()
2020

21+
# Gazebo only supports C++11 from version 5
22+
# http://answers.gazebosim.org/question/13869/ros-enabled-plugin-examples-use-c11/
23+
include (FindPkgConfig)
24+
if (PKG_CONFIG_FOUND)
25+
pkg_check_modules(GAZEBO gazebo)
26+
else()
27+
message(FATAL_ERROR "pkg-config is required; please install it")
28+
endif()
29+
if(${GAZEBO_VERSION} VERSION_LESS "5.0.0")
30+
else()
31+
set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")
32+
endif()
33+
2134
## Build only gazebo iob
2235
pkg_check_modules(omniorb omniORB4 REQUIRED)
2336
pkg_check_modules(omnidynamic omniDynamic4 REQUIRED)
2437
pkg_check_modules(openrtm_aist openrtm-aist REQUIRED)
2538
pkg_check_modules(openhrp3 openhrp3.1 REQUIRED)
2639
pkg_check_modules(hrpsys hrpsys-base REQUIRED)
27-
### hotfix for https://github.com/fkanehiro/hrpsys-base/pull/803
28-
list(GET hrpsys_INCLUDE_DIRS 0 hrpsys_first_incdir)
29-
list(APPEND hrpsys_INCLUDE_DIRS ${hrpsys_first_incdir}/hrpsys)
30-
list(APPEND hrpsys_INCLUDE_DIRS ${hrpsys_first_incdir}/hrpsys/idl)
3140
if(EXISTS ${hrpsys_SOURCE_DIR})
3241
set(ROBOTHARDWARE_SOURCE ${hrpsys_SOURCE_DIR}/src/rtc/RobotHardware)
3342
set(HRPEC_SOURCE ${hrpsys_SOURCE_DIR}/src/ec/hrpEC)
@@ -46,13 +55,6 @@ add_custom_target(hrpsys_gazebo_general_iob ALL DEPENDS RobotHardware_gazebo)
4655
add_dependencies(hrpsys_gazebo_general_iob hrpsys_gazebo_msgs_gencpp)
4756

4857
## Gazebo plugins
49-
include (FindPkgConfig)
50-
if (PKG_CONFIG_FOUND)
51-
pkg_check_modules(GAZEBO gazebo)
52-
else()
53-
message(FATAL_ERROR "pkg-config is required; please install it")
54-
endif()
55-
5658
include_directories( ${GAZEBO_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} ${openrtm_aist_INCLUDE_DIRS} ${openhrp3_INCLUDE_DIRS})
5759
link_directories( ${GAZEBO_LIBRARY_DIRS} ${openhrp3_LIBRARY_DIRS})
5860

hrpsys_gazebo_general/iob/iob.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
#include <cstdlib>
44
#include <cstring>
55
#include <vector>
6-
#include "io/iob.h"
6+
#include "hrpsys/io/iob.h"
77

88
#include <ros/ros.h>
99
#include <boost/algorithm/string.hpp>

hrpsys_gazebo_general/src/IOBPlugin.cpp

Lines changed: 26 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,13 @@
77

88
#include "IOBPlugin.h"
99

10+
#if __cplusplus >= 201103L
11+
#include <memory>
12+
using std::dynamic_pointer_cast;
13+
#else
14+
using boost::dynamic_pointer_cast;
15+
#endif
16+
1017
namespace gazebo
1118
{
1219
GZ_REGISTER_MODEL_PLUGIN(IOBPlugin);
@@ -240,10 +247,10 @@ void IOBPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
240247
ROS_ERROR("Force-Torque sensor: %s has invalid configuration", sensor_name.c_str());
241248
}
242249
// setup force sensor publishers
243-
boost::shared_ptr<std::vector<boost::shared_ptr<geometry_msgs::WrenchStamped> > > forceValQueue(new std::vector<boost::shared_ptr<geometry_msgs::WrenchStamped> >);
250+
shared_ptr<std::vector<shared_ptr<geometry_msgs::WrenchStamped> > > forceValQueue(new std::vector<shared_ptr<geometry_msgs::WrenchStamped> >);
244251
// forceValQueue->resize(this->force_sensor_average_window_size);
245252
for ( int i=0; i<this->force_sensor_average_window_size; i++ ){
246-
boost::shared_ptr<geometry_msgs::WrenchStamped> fbuf(new geometry_msgs::WrenchStamped);
253+
shared_ptr<geometry_msgs::WrenchStamped> fbuf(new geometry_msgs::WrenchStamped);
247254
forceValQueue->push_back(fbuf);
248255
}
249256
this->forceValQueueMap[sensor_name] = forceValQueue;
@@ -275,7 +282,7 @@ void IOBPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
275282
gzerr << ln << " not found\n";
276283
} else {
277284
// Get imu sensors
278-
msi.sensor = boost::dynamic_pointer_cast<sensors::ImuSensor>
285+
msi.sensor = dynamic_pointer_cast<sensors::ImuSensor>
279286
(sensors::SensorManager::Instance()->GetSensor
280287
(this->world->GetName() + "::" + msi.link->GetScopedName() + "::" + msi.sensor_name));
281288

@@ -377,7 +384,7 @@ void IOBPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
377384
// effort average
378385
effortValQueue.resize(0);
379386
for(int i = 0; i < this->effort_average_window_size; i++) {
380-
boost::shared_ptr<std::vector<double> > vbuf(new std::vector<double> (this->joints.size()));
387+
shared_ptr<std::vector<double> > vbuf(new std::vector<double> (this->joints.size()));
381388
effortValQueue.push_back(vbuf);
382389
}
383390
// for reference
@@ -779,7 +786,7 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
779786
// populate robotState from robot
780787
this->robotState.header.stamp = ros::Time(_curTime.sec, _curTime.nsec);
781788

782-
boost::shared_ptr<std::vector<double > > vbuf = effortValQueue.at(this->effort_average_cnt);
789+
shared_ptr<std::vector<double > > vbuf = effortValQueue.at(this->effort_average_cnt);
783790
// joint states
784791
for (unsigned int i = 0; i < this->joints.size(); ++i) {
785792
this->robotState.position[i] = this->joints[i]->GetAngle(0).Radian();
@@ -809,7 +816,7 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
809816
}
810817
if (this->use_joint_effort) {
811818
for (int j = 0; j < effortValQueue.size(); j++) {
812-
boost::shared_ptr<std::vector<double > > vbuf = effortValQueue.at(j);
819+
shared_ptr<std::vector<double > > vbuf = effortValQueue.at(j);
813820
for (int i = 0; i < this->joints.size(); i++) {
814821
this->robotState.effort[i] += vbuf->at(i);
815822
}
@@ -828,8 +835,8 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
828835
this->robotState.sensors.resize(this->forceSensorNames.size());
829836
for (unsigned int i = 0; i < this->forceSensorNames.size(); i++) {
830837
forceSensorMap::iterator it = this->forceSensors.find(this->forceSensorNames[i]);
831-
boost::shared_ptr<std::vector<boost::shared_ptr<geometry_msgs::WrenchStamped> > > forceValQueue = this->forceValQueueMap.find(this->forceSensorNames[i])->second;
832-
boost::shared_ptr<geometry_msgs::WrenchStamped> forceVal = forceValQueue->at(this->force_sensor_average_cnt);
838+
shared_ptr<std::vector<shared_ptr<geometry_msgs::WrenchStamped> > > forceValQueue = this->forceValQueueMap.find(this->forceSensorNames[i])->second;
839+
shared_ptr<geometry_msgs::WrenchStamped> forceVal = forceValQueue->at(this->force_sensor_average_cnt);
833840
if(it != this->forceSensors.end()) {
834841
physics::JointPtr jt = it->second.joint;
835842
if (!!jt) {
@@ -868,7 +875,7 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
868875
this->robotState.sensors[i].torque.y = 0;
869876
this->robotState.sensors[i].torque.z = 0;
870877
for ( int j=0; j<forceValQueue->size() ; j++ ){
871-
boost::shared_ptr<geometry_msgs::WrenchStamped> forceValBuf = forceValQueue->at(j);
878+
shared_ptr<geometry_msgs::WrenchStamped> forceValBuf = forceValQueue->at(j);
872879
this->robotState.sensors[i].force.x += forceValBuf->wrench.force.x;
873880
this->robotState.sensors[i].force.y += forceValBuf->wrench.force.y;
874881
this->robotState.sensors[i].force.z += forceValBuf->wrench.force.z;
@@ -897,9 +904,15 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
897904
if(!!sp) {
898905
this->robotState.Imus[i].name = this->imuSensorNames[i];
899906
this->robotState.Imus[i].frame_id = it->second.frame_id;
907+
#if __cplusplus >= 201103L
908+
math::Vector3 wLocal = sp->AngularVelocity();
909+
math::Vector3 accel = sp->LinearAcceleration();
910+
math::Quaternion imuRot = sp->Orientation();
911+
#else
900912
math::Vector3 wLocal = sp->GetAngularVelocity();
901913
math::Vector3 accel = sp->GetLinearAcceleration();
902914
math::Quaternion imuRot = sp->GetOrientation();
915+
#endif
903916
this->robotState.Imus[i].angular_velocity.x = wLocal.x;
904917
this->robotState.Imus[i].angular_velocity.y = wLocal.y;
905918
this->robotState.Imus[i].angular_velocity.z = wLocal.z;
@@ -948,7 +961,11 @@ void IOBPlugin::UpdatePID_Velocity_Control(double _dt) {
948961
static_cast<double>(this->robotState.kpv_velocity[i]) * this->errorTerms[i].qd_p;
949962

950963
// update max force
964+
#if __cplusplus >= 201103L
965+
this->joints[i]->SetParam("max_force", 0, this->joints[i]->GetEffortLimit(0));
966+
#else
951967
this->joints[i]->SetMaxForce(0, this->joints[i]->GetEffortLimit(0));
968+
#endif
952969
// clamp max velocity
953970
j_velocity = math::clamp(j_velocity, -max_vel, max_vel);
954971
#if 0

hrpsys_gazebo_general/src/IOBPlugin.h

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -42,12 +42,19 @@
4242

4343
#include "PubQueue.h"
4444

45+
#if __cplusplus >= 201103L
46+
#include <memory>
47+
using std::shared_ptr;
48+
#else
49+
using boost::shared_ptr;
50+
#endif
51+
4552
namespace gazebo
4653
{
47-
typedef boost::shared_ptr< sensors::ImuSensor > ImuSensorPtr;
54+
typedef shared_ptr< sensors::ImuSensor > ImuSensorPtr;
4855
typedef hrpsys_gazebo_msgs::JointCommand JointCommand;
4956
typedef hrpsys_gazebo_msgs::RobotState RobotState;
50-
typedef boost::shared_ptr< math::Pose > PosePtr;
57+
typedef shared_ptr< math::Pose > PosePtr;
5158

5259
class IOBPlugin : public ModelPlugin
5360
{
@@ -197,11 +204,11 @@ namespace gazebo
197204
// force sensor averaging
198205
int force_sensor_average_window_size;
199206
int force_sensor_average_cnt;
200-
std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<geometry_msgs::WrenchStamped> > > > forceValQueueMap;
207+
std::map<std::string, shared_ptr<std::vector<shared_ptr<geometry_msgs::WrenchStamped> > > > forceValQueueMap;
201208
// effort averaging
202209
int effort_average_cnt;
203210
int effort_average_window_size;
204-
std::vector< boost::shared_ptr<std::vector<double> > > effortValQueue;
211+
std::vector< shared_ptr<std::vector<double> > > effortValQueue;
205212
// stepping data publish cycle
206213
int publish_count;
207214
int publish_step;

hrpsys_gazebo_general/src/LIPPlugin.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,11 @@ namespace gazebo
133133
this->root_y_joint_->SetVelocity(0, 0);
134134
this->linear_joint_->SetVelocity(0, 0);
135135
// set position and velocity
136+
#if __cplusplus >= 201103L
137+
this->model_->SetWorldPose(base_pose);
138+
#else
136139
this->model_->SetWorldPose(base_pose, this->base_link_);
140+
#endif
137141
this->mass_link_->SetWorldPose(mass_pose);
138142
this->mass_link_->SetLinearVel(mass_velocity);
139143

@@ -157,7 +161,11 @@ namespace gazebo
157161
this->root_y_joint_->SetVelocity(0, 0);
158162
this->linear_joint_->SetVelocity(0, 0);
159163
// set position and velocity
164+
#if __cplusplus >= 201103L
165+
this->model_->SetWorldPose(base_pose);
166+
#else
160167
this->model_->SetWorldPose(base_pose, this->base_link_);
168+
#endif
161169
this->mass_link_->SetWorldPose(mass_pose);
162170
this->mass_link_->SetLinearVel(mass_velocity);
163171

hrpsys_gazebo_general/src/PubQueue.h

Lines changed: 19 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,12 @@
2727

2828
#include <ros/ros.h>
2929

30+
#if __cplusplus >= 201103L
31+
using std::shared_ptr;
32+
#else
33+
using boost::shared_ptr;
34+
#endif
35+
3036

3137
/// \brief Container for a (ROS publisher, outgoing message) pair.
3238
/// We'll have queues of these. Templated on a ROS message type.
@@ -49,21 +55,21 @@ template<class T>
4955
class PubQueue
5056
{
5157
public:
52-
typedef boost::shared_ptr<std::deque<boost::shared_ptr<
58+
typedef shared_ptr<std::deque<shared_ptr<
5359
PubMessagePair<T> > > > QueuePtr;
54-
typedef boost::shared_ptr<PubQueue<T> > Ptr;
60+
typedef shared_ptr<PubQueue<T> > Ptr;
5561

5662
private:
5763
/// \brief Our queue of outgoing messages.
5864
QueuePtr queue_;
5965
/// \brief Mutex to control access to the queue.
60-
boost::shared_ptr<boost::mutex> queue_lock_;
66+
shared_ptr<boost::mutex> queue_lock_;
6167
/// \brief Function that will be called when a new message is pushed on.
6268
boost::function<void()> notify_func_;
6369

6470
public:
6571
PubQueue(QueuePtr queue,
66-
boost::shared_ptr<boost::mutex> queue_lock,
72+
shared_ptr<boost::mutex> queue_lock,
6773
boost::function<void()> notify_func) :
6874
queue_(queue), queue_lock_(queue_lock), notify_func_(notify_func) {}
6975
~PubQueue() {}
@@ -73,15 +79,15 @@ class PubQueue
7379
/// \param[in] pub The ROS publisher to use to publish the message
7480
void push(T& msg, ros::Publisher& pub)
7581
{
76-
boost::shared_ptr<PubMessagePair<T> > el(new PubMessagePair<T>(msg, pub));
82+
shared_ptr<PubMessagePair<T> > el(new PubMessagePair<T>(msg, pub));
7783
boost::mutex::scoped_lock lock(*queue_lock_);
7884
queue_->push_back(el);
7985
notify_func_();
8086
}
8187

8288
/// \brief Pop all waiting messages off the queue.
8389
/// \param[out] els Place to store the popped messages
84-
void pop(std::vector<boost::shared_ptr<PubMessagePair<T> > >& els)
90+
void pop(std::vector<shared_ptr<PubMessagePair<T> > >& els)
8591
{
8692
boost::mutex::scoped_lock lock(*queue_lock_);
8793
while(!queue_->empty())
@@ -113,11 +119,11 @@ class PubMultiQueue
113119
/// \brief Service a given queue by popping outgoing message off it and
114120
/// publishing them.
115121
template <class T>
116-
void serviceFunc(boost::shared_ptr<PubQueue<T> > pq)
122+
void serviceFunc(shared_ptr<PubQueue<T> > pq)
117123
{
118-
std::vector<boost::shared_ptr<PubMessagePair<T> > > els;
124+
std::vector<shared_ptr<PubMessagePair<T> > > els;
119125
pq->pop(els);
120-
for(typename std::vector<boost::shared_ptr<PubMessagePair<T> > >::iterator it = els.begin();
126+
for(typename std::vector<shared_ptr<PubMessagePair<T> > >::iterator it = els.begin();
121127
it != els.end();
122128
++it)
123129
{
@@ -141,11 +147,11 @@ class PubMultiQueue
141147
/// least each type of publish message).
142148
/// \return Pointer to the newly created queue, good for calling push() on.
143149
template <class T>
144-
boost::shared_ptr<PubQueue<T> > addPub()
150+
shared_ptr<PubQueue<T> > addPub()
145151
{
146-
typename PubQueue<T>::QueuePtr queue(new std::deque<boost::shared_ptr<PubMessagePair<T> > >);
147-
boost::shared_ptr<boost::mutex> queue_lock(new boost::mutex);
148-
boost::shared_ptr<PubQueue<T> > pq(new PubQueue<T>(queue, queue_lock, boost::bind(&PubMultiQueue::notifyServiceThread, this)));
152+
typename PubQueue<T>::QueuePtr queue(new std::deque<shared_ptr<PubMessagePair<T> > >);
153+
shared_ptr<boost::mutex> queue_lock(new boost::mutex);
154+
shared_ptr<PubQueue<T> > pq(new PubQueue<T>(queue, queue_lock, boost::bind(&PubMultiQueue::notifyServiceThread, this)));
149155
boost::function<void()> f = boost::bind(&PubMultiQueue::serviceFunc<T>, this, pq);
150156
{
151157
boost::mutex::scoped_lock lock(service_funcs_lock_);

0 commit comments

Comments
 (0)