button_example.cpp
Go to the documentation of this file.
1 /*
2  * Button Example for Rosserial
3  */
4 
5 #include "mbed.h"
6 #include <ros.h>
7 #include <std_msgs/Bool.h>
8 
9 #ifdef TARGET_LPC1768
10 PinName button = p20;
11 #elif defined(TARGET_KL25Z)
12 PinName button = D10;
13 #elif defined(TARGET_NUCLEO_F401RE)
14 PinName button = USER_BUTTON;
15 #else
16 #error "You need to specify a pin for the button"
17 #endif
18 
20 
21 std_msgs::Bool pushed_msg;
23 
24 DigitalIn button_pin(button);
25 DigitalOut led_pin(LED1);
26 
30 bool published = true;
31 
32 Timer t;
33 int main() {
34  t.start();
35  nh.initNode();
37 
38  //Enable the pullup resistor on the button
39  button_pin.mode(PullUp);
40 
41  //The button is a normally button
43 
44  while (1) {
45  bool reading = ! button_pin;
46 
47  if (last_reading!= reading) {
48  last_debounce_time = t.read_ms();
49  published = false;
50  }
51 
52  //if the button value has not changed for the debounce delay, we know its stable
53  if ( !published && (t.read_ms() - last_debounce_time) > debounce_delay) {
54  led_pin = reading;
55  pushed_msg.data = reading;
57  published = true;
58  }
59 
60  last_reading = reading;
61 
62  nh.spinOnce();
63  }
64 }
65 
void publish(const boost::shared_ptr< M > &message) const
DigitalOut led_pin(LED1)
long last_debounce_time
ros::NodeHandle nh
DigitalIn button_pin(button)
int main()
long debounce_delay
bool last_reading
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Timer t
ros::Publisher pub_button("pushed",&pushed_msg)
bool published
std_msgs::Bool pushed_msg


rosserial_mbed
Author(s): Gary Servin
autogenerated on Fri Jun 7 2019 22:02:48