summaryrefslogtreecommitdiff
path: root/dev-ros/rosserial_server/files/boost162.patch
blob: d644d409f9e6db79165427428edf16675614ff84 (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
commit f8a46f3142444c854233a85f7a5ec7b91b5378a6
Author: Malte Splietker <splietker@users.noreply.github.com>
Date:   Wed Oct 5 04:26:00 2016 +0200

    Fixing build errors for boost >=1.60 (#226) (#250)
    
    Signed-off-by: Malte Splietker <maltespl@mail.upb.de>

diff --git a/rosserial_server/include/rosserial_server/session.h b/rosserial_server/include/rosserial_server/session.h
index 86b9baa..ebd109a 100644
--- a/rosserial_server/include/rosserial_server/session.h
+++ b/rosserial_server/include/rosserial_server/session.h
@@ -499,7 +499,7 @@ private:
   boost::asio::deadline_timer ros_spin_timer_;
   std::string require_param_name_;
 
-  std::map<uint16_t, boost::function<void(ros::serialization::IStream)> > callbacks_;
+  std::map<uint16_t, boost::function<void(ros::serialization::IStream&)> > callbacks_;
   std::map<uint16_t, PublisherPtr> publishers_;
   std::map<uint16_t, SubscriberPtr> subscribers_;
   std::map<std::string, ServiceClientPtr> services_;
diff --git a/rosserial_server/include/rosserial_server/topic_handlers.h b/rosserial_server/include/rosserial_server/topic_handlers.h
index 666f3fc..2f367c3 100644
--- a/rosserial_server/include/rosserial_server/topic_handlers.h
+++ b/rosserial_server/include/rosserial_server/topic_handlers.h
@@ -93,7 +93,7 @@ typedef boost::shared_ptr<Publisher> PublisherPtr;
 class Subscriber {
 public:
   Subscriber(ros::NodeHandle& nh, rosserial_msgs::TopicInfo& topic_info,
-      boost::function<void(std::vector<uint8_t> buffer)> write_fn)
+      boost::function<void(std::vector<uint8_t>& buffer)> write_fn)
     : write_fn_(write_fn) {
     ros::SubscribeOptions opts;
     opts.init<topic_tools::ShapeShifter>(
@@ -119,7 +119,7 @@ private:
   }
 
   ros::Subscriber subscriber_;
-  boost::function<void(std::vector<uint8_t> buffer)> write_fn_;
+  boost::function<void(std::vector<uint8_t>& buffer)> write_fn_;
 };
 
 typedef boost::shared_ptr<Subscriber> SubscriberPtr;
@@ -127,7 +127,7 @@ typedef boost::shared_ptr<Subscriber> SubscriberPtr;
 class ServiceClient {
 public:
   ServiceClient(ros::NodeHandle& nh, rosserial_msgs::TopicInfo& topic_info,
-      boost::function<void(std::vector<uint8_t> buffer, const uint16_t topic_id)> write_fn)
+      boost::function<void(std::vector<uint8_t>& buffer, const uint16_t topic_id)> write_fn)
     : write_fn_(write_fn) {
     topic_id_ = -1;
     if (!service_info_service_.isValid()) {
@@ -185,7 +185,7 @@ private:
   topic_tools::ShapeShifter response_message_;
   ros::ServiceClient service_client_;
   static ros::ServiceClient service_info_service_;
-  boost::function<void(std::vector<uint8_t> buffer, const uint16_t topic_id)> write_fn_;
+  boost::function<void(std::vector<uint8_t>& buffer, const uint16_t topic_id)> write_fn_;
   std::string service_md5_;
   std::string request_message_md5_;
   std::string response_message_md5_;