14 #include <std_msgs/Float32MultiArray.h> 20 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE) 23 #error "You need to specify a pin for the sensor" 36 void beep(
float freq,
float time)
38 buzzer.period(1.0 / freq);
44 void messageCb(
const std_msgs::Float32MultiArray& msg)
51 beep(msg.data[0], msg.data[1]);
void messageCb(const std_msgs::Float32MultiArray &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::Subscriber< std_msgs::Float32MultiArray > sub("buzzer",&messageCb)
void beep(float freq, float time)