4 #include <boost/circular_buffer.hpp>
6 #include "look_caresses_pkg/platform_sensors.h"
7 #include "look_caresses_pkg/platform_control.h"
9 #define averageNum 20 // number of values to consider in the average for the sonar range
15 ros::Publisher pubPlat;
16 ros::Subscriber subRange;
17 boost::circular_buffer<float> sonarMsgs;
19 void sonarCallback(
const sensor_msgs::Range &sensor_range);
24 B_approach (ros::NodeHandle nh, ros::Publisher pubPlat);
28 #endif // B_APPROACH_H
int main()
main for approachin phase. MiRo goes straight until the sensor detect something (ideally the user han...
B_approach(ros::NodeHandle nh, ros::Publisher pubPlat)
Costructor for phase B task.