boost162.patch 2.8 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162
  1. commit f8a46f3142444c854233a85f7a5ec7b91b5378a6
  2. Author: Malte Splietker <splietker@users.noreply.github.com>
  3. Date: Wed Oct 5 04:26:00 2016 +0200
  4. Fixing build errors for boost >=1.60 (#226) (#250)
  5. Signed-off-by: Malte Splietker <maltespl@mail.upb.de>
  6. diff --git a/rosserial_server/include/rosserial_server/session.h b/rosserial_server/include/rosserial_server/session.h
  7. index 86b9baa..ebd109a 100644
  8. --- a/rosserial_server/include/rosserial_server/session.h
  9. +++ b/rosserial_server/include/rosserial_server/session.h
  10. @@ -499,7 +499,7 @@ private:
  11. boost::asio::deadline_timer ros_spin_timer_;
  12. std::string require_param_name_;
  13. - std::map<uint16_t, boost::function<void(ros::serialization::IStream)> > callbacks_;
  14. + std::map<uint16_t, boost::function<void(ros::serialization::IStream&)> > callbacks_;
  15. std::map<uint16_t, PublisherPtr> publishers_;
  16. std::map<uint16_t, SubscriberPtr> subscribers_;
  17. std::map<std::string, ServiceClientPtr> services_;
  18. diff --git a/rosserial_server/include/rosserial_server/topic_handlers.h b/rosserial_server/include/rosserial_server/topic_handlers.h
  19. index 666f3fc..2f367c3 100644
  20. --- a/rosserial_server/include/rosserial_server/topic_handlers.h
  21. +++ b/rosserial_server/include/rosserial_server/topic_handlers.h
  22. @@ -93,7 +93,7 @@ typedef boost::shared_ptr<Publisher> PublisherPtr;
  23. class Subscriber {
  24. public:
  25. Subscriber(ros::NodeHandle& nh, rosserial_msgs::TopicInfo& topic_info,
  26. - boost::function<void(std::vector<uint8_t> buffer)> write_fn)
  27. + boost::function<void(std::vector<uint8_t>& buffer)> write_fn)
  28. : write_fn_(write_fn) {
  29. ros::SubscribeOptions opts;
  30. opts.init<topic_tools::ShapeShifter>(
  31. @@ -119,7 +119,7 @@ private:
  32. }
  33. ros::Subscriber subscriber_;
  34. - boost::function<void(std::vector<uint8_t> buffer)> write_fn_;
  35. + boost::function<void(std::vector<uint8_t>& buffer)> write_fn_;
  36. };
  37. typedef boost::shared_ptr<Subscriber> SubscriberPtr;
  38. @@ -127,7 +127,7 @@ typedef boost::shared_ptr<Subscriber> SubscriberPtr;
  39. class ServiceClient {
  40. public:
  41. ServiceClient(ros::NodeHandle& nh, rosserial_msgs::TopicInfo& topic_info,
  42. - boost::function<void(std::vector<uint8_t> buffer, const uint16_t topic_id)> write_fn)
  43. + boost::function<void(std::vector<uint8_t>& buffer, const uint16_t topic_id)> write_fn)
  44. : write_fn_(write_fn) {
  45. topic_id_ = -1;
  46. if (!service_info_service_.isValid()) {
  47. @@ -185,7 +185,7 @@ private:
  48. topic_tools::ShapeShifter response_message_;
  49. ros::ServiceClient service_client_;
  50. static ros::ServiceClient service_info_service_;
  51. - boost::function<void(std::vector<uint8_t> buffer, const uint16_t topic_id)> write_fn_;
  52. + boost::function<void(std::vector<uint8_t>& buffer, const uint16_t topic_id)> write_fn_;
  53. std::string service_md5_;
  54. std::string request_message_md5_;
  55. std::string response_message_md5_;