Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed ros_lib_kinetic
Fork of Nucleo_i2c_pcf8574 by
main.cpp@1:b3a2c43439bd, 2018-10-15 (annotated)
- Committer:
- WeberYang
- Date:
- Mon Oct 15 09:53:46 2018 +0000
- Revision:
- 1:b3a2c43439bd
- Parent:
- 0:daf4d39b8c98
Using PB_8(SCL) PB_9(SDA) to control DI/DO,; ros node
Who changed what in which revision?
| User | Revision | Line number | New contents of line |
|---|---|---|---|
| aAXEe | 0:daf4d39b8c98 | 1 | #include "mbed.h" |
| WeberYang | 1:b3a2c43439bd | 2 | #include <ros.h> |
| WeberYang | 1:b3a2c43439bd | 3 | #include <ros/time.h> |
| WeberYang | 1:b3a2c43439bd | 4 | #include <std_msgs/Int16.h> |
| WeberYang | 1:b3a2c43439bd | 5 | #define PCF8574_ADDR (0x40) |
| WeberYang | 1:b3a2c43439bd | 6 | #define PCF8574_ADDR_1 (0x40) |
| WeberYang | 1:b3a2c43439bd | 7 | #define PCF8574_ADDR_2 (0x42) |
| WeberYang | 1:b3a2c43439bd | 8 | |
| WeberYang | 1:b3a2c43439bd | 9 | I2C i2c(PB_9, PB_8); |
| aAXEe | 0:daf4d39b8c98 | 10 | |
| WeberYang | 1:b3a2c43439bd | 11 | //Serial pc(SERIAL_TX, SERIAL_RX); |
| WeberYang | 1:b3a2c43439bd | 12 | //========================== |
| WeberYang | 1:b3a2c43439bd | 13 | bool pcf8574_write(uint8_t data,uint8_t address); |
| WeberYang | 1:b3a2c43439bd | 14 | bool pcf8574_read(uint8_t* data,uint8_t address); |
| WeberYang | 1:b3a2c43439bd | 15 | int DO_write(uint8_t value,uint8_t address); |
| WeberYang | 1:b3a2c43439bd | 16 | int DI_read(uint8_t address); |
| WeberYang | 1:b3a2c43439bd | 17 | //====================================================================== |
| WeberYang | 1:b3a2c43439bd | 18 | ros::NodeHandle nh; |
| WeberYang | 1:b3a2c43439bd | 19 | std_msgs::Int16 DO; |
| WeberYang | 1:b3a2c43439bd | 20 | void DO_ACT(const std_msgs::Int16 &msg){ |
| WeberYang | 1:b3a2c43439bd | 21 | DO_write(msg.data, PCF8574_ADDR_1); |
| WeberYang | 1:b3a2c43439bd | 22 | } |
| WeberYang | 1:b3a2c43439bd | 23 | ros::Subscriber<std_msgs::Int16> ACT_sub("DO_data", &DO_ACT); |
| aAXEe | 0:daf4d39b8c98 | 24 | |
| WeberYang | 1:b3a2c43439bd | 25 | std_msgs::Int16 DI; |
| WeberYang | 1:b3a2c43439bd | 26 | ros::Publisher DI_pub("DI_pub", &DI); |
| WeberYang | 1:b3a2c43439bd | 27 | //====================================================================== |
| aAXEe | 0:daf4d39b8c98 | 28 | |
| WeberYang | 1:b3a2c43439bd | 29 | bool pcf8574_write(uint8_t data,uint8_t address){ |
| WeberYang | 1:b3a2c43439bd | 30 | return i2c.write(address, (char*) &data, 1, 0) == 0; |
| aAXEe | 0:daf4d39b8c98 | 31 | } |
| aAXEe | 0:daf4d39b8c98 | 32 | |
| WeberYang | 1:b3a2c43439bd | 33 | bool pcf8574_read(uint8_t* data,uint8_t address){ |
| WeberYang | 1:b3a2c43439bd | 34 | return i2c.read(address, (char*) data, 1, 0) == 0; |
| aAXEe | 0:daf4d39b8c98 | 35 | } |
| aAXEe | 0:daf4d39b8c98 | 36 | |
| WeberYang | 1:b3a2c43439bd | 37 | int DO_write(uint8_t value,uint8_t address){ |
| WeberYang | 1:b3a2c43439bd | 38 | int ret; |
| WeberYang | 1:b3a2c43439bd | 39 | |
| WeberYang | 1:b3a2c43439bd | 40 | ret = pcf8574_write(value,address); |
| WeberYang | 1:b3a2c43439bd | 41 | |
| WeberYang | 1:b3a2c43439bd | 42 | return ret; |
| WeberYang | 1:b3a2c43439bd | 43 | } |
| WeberYang | 1:b3a2c43439bd | 44 | int DI_read(uint8_t address){ |
| aAXEe | 0:daf4d39b8c98 | 45 | int ret; |
| aAXEe | 0:daf4d39b8c98 | 46 | uint8_t data=0; |
| WeberYang | 1:b3a2c43439bd | 47 | |
| WeberYang | 1:b3a2c43439bd | 48 | ret = pcf8574_read(&data,address); |
| aAXEe | 0:daf4d39b8c98 | 49 | if(!ret) return -2; |
| aAXEe | 0:daf4d39b8c98 | 50 | |
| aAXEe | 0:daf4d39b8c98 | 51 | return data; |
| aAXEe | 0:daf4d39b8c98 | 52 | } |
| aAXEe | 0:daf4d39b8c98 | 53 | |
| WeberYang | 1:b3a2c43439bd | 54 | |
| aAXEe | 0:daf4d39b8c98 | 55 | int main() |
| aAXEe | 0:daf4d39b8c98 | 56 | { |
| WeberYang | 1:b3a2c43439bd | 57 | nh.initNode(); |
| WeberYang | 1:b3a2c43439bd | 58 | nh.advertise(DI_pub); |
| WeberYang | 1:b3a2c43439bd | 59 | nh.subscribe(ACT_sub); |
| WeberYang | 1:b3a2c43439bd | 60 | // printf("Hello PCF8574\n"); |
| aAXEe | 0:daf4d39b8c98 | 61 | while (1) { |
| WeberYang | 1:b3a2c43439bd | 62 | // pc.printf("Read DI=%i\r\n", DI_read(PCF8574_ADDR_2)); |
| WeberYang | 1:b3a2c43439bd | 63 | |
| WeberYang | 1:b3a2c43439bd | 64 | // DO_PC_9 = 0; |
| WeberYang | 1:b3a2c43439bd | 65 | |
| WeberYang | 1:b3a2c43439bd | 66 | // wait(0.1); |
| WeberYang | 1:b3a2c43439bd | 67 | DI.data = DI_read(PCF8574_ADDR_2); |
| WeberYang | 1:b3a2c43439bd | 68 | DI_pub.publish( &DI); |
| WeberYang | 1:b3a2c43439bd | 69 | nh.spinOnce(); |
| WeberYang | 1:b3a2c43439bd | 70 | wait_ms(100); |
| aAXEe | 0:daf4d39b8c98 | 71 | } |
| aAXEe | 0:daf4d39b8c98 | 72 | |
| aAXEe | 0:daf4d39b8c98 | 73 | } |
| WeberYang | 1:b3a2c43439bd | 74 |
