Dependencies:   mbed ros_lib_kinetic

Files at this revision

API Documentation at this revision

Comitter:
surpace0924
Date:
Tue Oct 29 05:38:24 2019 +0000
Commit message:
init;

Changed in this revision

DebugSerial.lib Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
mbed.bld Show annotated file Show diff for this revision Revisions of this file
ros_lib_kinetic.lib Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/DebugSerial.lib	Tue Oct 29 05:38:24 2019 +0000
@@ -0,0 +1,1 @@
+https://github.com/robocon-ichinoseki-Ateam/DebugSerial/#c55eec04d41a4d8d81b060edf30859e36a12ef8c
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Tue Oct 29 05:38:24 2019 +0000
@@ -0,0 +1,80 @@
+#include "mbed.h"
+#include <ros.h>
+#include <std_msgs/Float32MultiArray.h>
+#include <std_msgs/Int32.h>
+
+float TH = 0;
+double a[9];
+bool onLine[7] = {false};
+int binarized_data = 0;
+void messageCb(const std_msgs::Int32 &msg)
+{
+    binarized_data = msg.data;
+}
+
+Ticker flipper;
+ros::NodeHandle nh;
+std_msgs::Float32MultiArray send_data;
+ros::Publisher pub_to_ros("line_sensor/y", &send_data);
+ros::Subscriber<std_msgs::Int32> sub("line_sensor/binarized/y", &messageCb);
+
+
+void flip() {
+    for(int i = 0; i < 9; i++)
+    {
+        send_data.data[i] = a[i];
+    }
+
+    // ROSへデータを送信
+    pub_to_ros.publish(&send_data);
+}
+
+AnalogIn sensor[] = {
+    AnalogIn(PA_7),
+    AnalogIn(PA_6),
+    AnalogIn(PA_5),
+    AnalogIn(PA_4),
+    AnalogIn(PB_0),
+    AnalogIn(PB_1),
+    AnalogIn(PA_3),
+    AnalogIn(PA_1),
+    AnalogIn(PA_0)};
+
+DigitalOut leds[] = {
+    DigitalOut(PA_9),
+    DigitalOut(PA_10),
+    DigitalOut(PA_8),
+    DigitalOut(PB_7),
+    DigitalOut(PB_6),
+    DigitalOut(PF_0),
+    DigitalOut(PF_1)};
+
+int main()
+{
+    nh.initNode();
+    nh.advertise(pub_to_ros);
+    nh.subscribe(sub);
+    
+    // 送信パケットの初期化
+    send_data.data_length = 9;
+    send_data.data = (float *)malloc(sizeof(float) * send_data.data_length);
+    for (int i = 0; i < send_data.data_length; i++)
+        send_data.data[i] = 0.0;
+
+    // 送信関数を一定周期で呼び出す
+    flipper.attach(&flip, 0.02);
+    
+    while (1)
+    {
+        for (int i = 0; i < 9; i++)
+        {
+            a[i] = sensor[i];
+        }
+        for (int i = 0; i < 7; i++)
+        {   
+            leds[i] = (int)((binarized_data >> i) & 1);
+        }
+
+        nh.spinOnce();
+    }
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed.bld	Tue Oct 29 05:38:24 2019 +0000
@@ -0,0 +1,1 @@
+https://os.mbed.com/users/mbed_official/code/mbed/builds/65be27845400
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros_lib_kinetic.lib	Tue Oct 29 05:38:24 2019 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/garyservin/code/ros_lib_kinetic/#a849bf78d77f