ros_serial for mbed updated to work with ROS Hydro. Library still needs to be debugged
Embed:
(wiki syntax)
Show/hide line numbers
Button_example.cpp
00001 //#define COMPILE_BUTTON_EXAMPLE_CODE_ROSSERIAL 00002 #ifdef COMPILE_BUTTON_EXAMPLE_CODE_ROSSERIAL 00003 00004 /* 00005 * Button Example for Rosserial 00006 */ 00007 00008 #include "mbed.h" 00009 #include <ros.h> 00010 #include <std_msgs/Bool.h> 00011 00012 00013 ros::NodeHandle nh; 00014 00015 std_msgs::Bool pushed_msg; 00016 ros::Publisher pub_button("pushed", &pushed_msg); 00017 00018 DigitalIn button_pin(p8); 00019 DigitalOut led_pin(LED1); 00020 00021 bool last_reading; 00022 long last_debounce_time=0; 00023 long debounce_delay=50; 00024 bool published = true; 00025 00026 Timer t; 00027 int main() { 00028 t.start(); 00029 nh.initNode(); 00030 nh.advertise(pub_button); 00031 00032 //Enable the pullup resistor on the button 00033 button_pin.mode(PullUp); 00034 00035 //The button is a normally button 00036 last_reading = ! button_pin; 00037 00038 while (1) { 00039 bool reading = ! button_pin; 00040 00041 if (last_reading!= reading) { 00042 last_debounce_time = t.read_ms(); 00043 published = false; 00044 } 00045 00046 //if the button value has not changed for the debounce delay, we know its stable 00047 if ( !published && (t.read_ms() - last_debounce_time) > debounce_delay) { 00048 led_pin = reading; 00049 pushed_msg.data = reading; 00050 pub_button.publish(&pushed_msg); 00051 published = true; 00052 } 00053 00054 last_reading = reading; 00055 00056 nh.spinOnce(); 00057 } 00058 } 00059 #endif
Generated on Sun Jul 17 2022 00:31:54 by 1.7.2