src
examples
button_example
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
19
ros::NodeHandle
nh
;
20
21
std_msgs::Bool
pushed_msg
;
22
ros::Publisher
pub_button
(
"pushed"
, &
pushed_msg
);
23
24
DigitalIn
button_pin
(button);
25
DigitalOut
led_pin
(LED1);
26
27
bool
last_reading
;
28
long
last_debounce_time
=0;
29
long
debounce_delay
=50;
30
bool
published
=
true
;
31
32
Timer
t
;
33
int
main
() {
34
t
.start();
35
nh
.initNode();
36
nh
.
advertise
(
pub_button
);
37
38
//Enable the pullup resistor on the button
39
button_pin
.mode(PullUp);
40
41
//The button is a normally button
42
last_reading
= !
button_pin
;
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;
56
pub_button
.
publish
(&
pushed_msg
);
57
published
=
true
;
58
}
59
60
last_reading
= reading;
61
62
nh
.spinOnce();
63
}
64
}
65
ros::Publisher
main
int main()
Definition:
button_example.cpp:33
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
led_pin
DigitalOut led_pin(LED1)
nh
ros::NodeHandle nh
Definition:
button_example.cpp:19
button_pin
DigitalIn button_pin(button)
published
bool published
Definition:
button_example.cpp:30
pushed_msg
std_msgs::Bool pushed_msg
Definition:
button_example.cpp:21
pub_button
ros::Publisher pub_button("pushed", &pushed_msg)
last_reading
bool last_reading
Definition:
button_example.cpp:27
t
Timer t
Definition:
button_example.cpp:32
debounce_delay
long debounce_delay
Definition:
button_example.cpp:29
last_debounce_time
long last_debounce_time
Definition:
button_example.cpp:28
ros::NodeHandle
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08