ichinoseki_Bteam_2019 / Mbed 2 deprecated ArmNode

Dependencies:   IMU SPI_Encoder mbed Path PID Motor Inertia ros_lib_kinetic Kinematics Mycan

Revision:
0:8b0869cb7fa8
Child:
1:0839d3bc46c2
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Mon Jul 22 17:49:09 2019 +0000
@@ -0,0 +1,38 @@
+#include "mbed.h"
+#include <ros.h>
+#include <std_msgs/Float32MultiArray.h>
+#include "set.h"
+
+#define inertia M*R*R //moment of inertia
+
+float voltage;
+float resistance;
+float kt;
+float ke;
+float *w;
+float torque;
+float pwm = 1 / voltage * ((resistance * (torque) / kt) + (*w * ke));
+
+ros::NodeHandle nh;
+DigitalOut myled(LED1);
+
+float coordinate[3] = {};
+
+
+void callback(const std_msgs::Float32MultiArray& msg) {
+    int size = msg.data_length;
+    for (int i = 0; i < size; i++)
+        coordinate[i] = msg.data[i];
+}
+
+ros::Subscriber<std_msgs::Float32MultiArray> sub("bath_towel", callback);
+
+
+int main() {
+    nh.initNode();
+    nh.subscribe(sub);
+    while(1) {
+        nh.spinOnce();
+        wait_ms(1);
+    }
+}