This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.

Dependencies:   rosserial_mbed_lib mbed Servo

Committer:
nucho
Date:
Fri Aug 19 09:06:16 2011 +0000
Revision:
0:06fc856e99ca

        

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 0:06fc856e99ca 1 //#define COMPILE_BUTTON_EXAMPLE_CODE_ROSSERIAL
nucho 0:06fc856e99ca 2 #ifdef COMPILE_BUTTON_EXAMPLE_CODE_ROSSERIAL
nucho 0:06fc856e99ca 3
nucho 0:06fc856e99ca 4 /*
nucho 0:06fc856e99ca 5 * Button Example for Rosserial
nucho 0:06fc856e99ca 6 */
nucho 0:06fc856e99ca 7
nucho 0:06fc856e99ca 8 #include "mbed.h"
nucho 0:06fc856e99ca 9 #include <ros.h>
nucho 0:06fc856e99ca 10 #include <std_msgs/Bool.h>
nucho 0:06fc856e99ca 11
nucho 0:06fc856e99ca 12
nucho 0:06fc856e99ca 13 ros::NodeHandle nh;
nucho 0:06fc856e99ca 14
nucho 0:06fc856e99ca 15 std_msgs::Bool pushed_msg;
nucho 0:06fc856e99ca 16 ros::Publisher pub_button("pushed", &pushed_msg);
nucho 0:06fc856e99ca 17
nucho 0:06fc856e99ca 18 DigitalIn button_pin(p8);
nucho 0:06fc856e99ca 19 DigitalOut led_pin(LED1);
nucho 0:06fc856e99ca 20
nucho 0:06fc856e99ca 21 bool last_reading;
nucho 0:06fc856e99ca 22 long last_debounce_time=0;
nucho 0:06fc856e99ca 23 long debounce_delay=50;
nucho 0:06fc856e99ca 24 bool published = true;
nucho 0:06fc856e99ca 25
nucho 0:06fc856e99ca 26 Timer t;
nucho 0:06fc856e99ca 27 int main() {
nucho 0:06fc856e99ca 28 t.start();
nucho 0:06fc856e99ca 29 nh.initNode();
nucho 0:06fc856e99ca 30 nh.advertise(pub_button);
nucho 0:06fc856e99ca 31
nucho 0:06fc856e99ca 32 //Enable the pullup resistor on the button
nucho 0:06fc856e99ca 33 button_pin.mode(PullUp);
nucho 0:06fc856e99ca 34
nucho 0:06fc856e99ca 35 //The button is a normally button
nucho 0:06fc856e99ca 36 last_reading = ! button_pin;
nucho 0:06fc856e99ca 37
nucho 0:06fc856e99ca 38 while (1) {
nucho 0:06fc856e99ca 39 bool reading = ! button_pin;
nucho 0:06fc856e99ca 40
nucho 0:06fc856e99ca 41 if (last_reading!= reading) {
nucho 0:06fc856e99ca 42 last_debounce_time = t.read_ms();
nucho 0:06fc856e99ca 43 published = false;
nucho 0:06fc856e99ca 44 }
nucho 0:06fc856e99ca 45
nucho 0:06fc856e99ca 46 //if the button value has not changed for the debounce delay, we know its stable
nucho 0:06fc856e99ca 47 if ( !published && (t.read_ms() - last_debounce_time) > debounce_delay) {
nucho 0:06fc856e99ca 48 led_pin = reading;
nucho 0:06fc856e99ca 49 pushed_msg.data = reading;
nucho 0:06fc856e99ca 50 pub_button.publish(&pushed_msg);
nucho 0:06fc856e99ca 51 published = true;
nucho 0:06fc856e99ca 52 }
nucho 0:06fc856e99ca 53
nucho 0:06fc856e99ca 54 last_reading = reading;
nucho 0:06fc856e99ca 55
nucho 0:06fc856e99ca 56 nh.spinOnce();
nucho 0:06fc856e99ca 57 }
nucho 0:06fc856e99ca 58 }
nucho 0:06fc856e99ca 59 #endif