Revision 482adb6d 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

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

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

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

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

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

Also available in: Unified diff