Revision 888a909b server/include/MiddlewareROS.h

View differences:

server/include/MiddlewareROS.h
50 50
    #include "ROS/AnimationCallbackWrapperROS.h"
51 51
    #include "ROS/SpeechCallbackWrapperROS.h"
52 52
#endif
53
#include <boost/shared_ptr.hpp>
53
#include <memory>
54 54

  
55 55
#define ROS_ACTION_CALL_TIMEOUT 30.0
56 56

  
......
66 66
    void init(){};
67 67
    void tick(){};
68 68

  
69
    boost::shared_ptr<Utterance> tts_call(std::string text){
70
        return boost::shared_ptr<Utterance>(new Utterance());
69
    std::shared_ptr<Utterance> tts_call(std::string text){
70
        return std::shared_ptr<Utterance>(new Utterance());
71 71
    }
72 72

  
73 73
#else
......
76 76
    ~MiddlewareROS();
77 77
    void init();
78 78
    void tick();
79
    boost::shared_ptr<Utterance> tts_call(std::string text);
79
    std::shared_ptr<Utterance> tts_call(std::string text);
80 80

  
81 81
private:
82
    //boost::shared_ptr<ros::NodeHandle> node_handle;
82
    //std::shared_ptr<ros::NodeHandle> node_handle;
83 83
    ros::NodeHandle *ros_node_handle;
84 84
    bool tick_necessary;
85 85
    //listen to tf tree
86 86
    tf2_ros::Buffer tfBuffer;
87
    boost::shared_ptr<tf2_ros::TransformListener> tfListener;
87
    std::shared_ptr<tf2_ros::TransformListener> tfListener;
88 88

  
89 89
    //FIXME: These pointers are never destroyed. Shouldn't they be shared_ptrs?
90 90
    AnimationCallbackWrapper *animation_action_server;

Also available in: Unified diff