Looking for Caresses
SoRo project to let Miro interact as a pet would do
 All Classes Functions Variables Pages
C_interaction.h
1 #ifndef C_INTERACTION_H
2 #define C_INTERACTION_H
3 
4 #include <ros/ros.h>
5 #include "std_msgs/String.h"
6 #include "look_caresses_pkg/platform_control.h"
7 
8 class C_interaction {
9 private:
10  bool notRead;
11  int positiveApproach;
12  int negativeApproach;
13  int counterSound;
14  ros::NodeHandle nh;
15  ros::Subscriber subClass;
16  ros::Publisher pubPlat;
17 
18  void classCallback(const std_msgs::String &pattern);
19  void showHappiness(int loneliness);
20  void subTopics();
21  void unsubTopics();
22 
23 public:
24  C_interaction(ros::NodeHandle nh, ros::Publisher pubPlat);
25  int main(int loneliness);
26 };
27 
28 #endif // C_INTERACTION_H
int main(int loneliness)
Main for Task C. The task updates the loneliness value if MiRo receive caresses, and make MiRo acts h...
C_interaction(ros::NodeHandle nh, ros::Publisher pubPlat)
Costructor for phase C task.