7th_DENSOU / Mbed 2 deprecated NHK2021_Throw

Dependencies:   mbed CalPID MotorController ros_lib_melodic Encoder

Files at this revision

API Documentation at this revision

Comitter:
koheim
Date:
Sun Jul 25 13:58:43 2021 +0000
Parent:
3:7c90e5389b84
Commit message:
a

Changed in this revision

main.cpp Show annotated file Show diff for this revision Revisions of this file
ros_lib_melodic.lib Show annotated file Show diff for this revision Revisions of this file
--- a/main.cpp	Thu Jul 22 07:25:21 2021 +0000
+++ b/main.cpp	Sun Jul 25 13:58:43 2021 +0000
@@ -3,6 +3,8 @@
 #define RESOLUTION 500
 #include "CalPID.h"
 #include "MotorController.h"
+#include <ros.h>
+#include <geometry_msgs/Point.h>
 #define DELTA_T 0.001
 
 #define TIME_TURNING 0.8
@@ -10,11 +12,10 @@
 #define OMEGA_MAX 5
 
 ////////////////////////////////////////
-#define THROW_SPEED 10  //13.33
+#define THROW_SPEED 11.9
 
 ///////////////////////////////////////
-#define THROW_FIN 75
-//#define THROW_FIN 35
+#define THROW_FIN 95
 #define BOTTOM_ANGLE 0.5
 #define STOP_ANGLE 0.1
 
@@ -26,6 +27,7 @@
 Ticker ticker;
 DigitalOut led1(LED1);
 DigitalOut led2(LED2);
+DigitalOut led3(LED3);
 
 //CalPID speed_pid(0.9281,0,0.0002486,DELTA_T,DUTY_MAX);
 //CalPID angle_duty_pid(0,0,0,DELTA_T,DUTY_MAX);
@@ -39,6 +41,11 @@
 Ec1multi ec(p17,p18,RESOLUTION);  //2逓倍用class
 MotorController motor(p21,p22,DELTA_T,ec,speed_pid,angle_duty_pid,angle_omega_pid);
 
+float shot = 0;
+
+void throwCallback(const geometry_msgs::Point &throw_state){
+    shot = throw_state.x; //1になったら発射
+}
 
 double convertRad(double degree)
 {
@@ -155,11 +162,15 @@
     ticker.attach(&inputDuty,DELTA_T);
     wait(dead_time);
     ticker.detach();
+}
 
-}
-int main ()
-{
+ros::NodeHandle nh;
+ros::Subscriber<geometry_msgs::Point> sub("/throw",&throwCallback);
 
+int main(){
+    nh.getHardware()->setBaud(115200);
+    nh.initNode();
+    nh.subscribe(sub);
     NVIC_SetPriority(TIMER3_IRQn, 5);
 /////////////////////////////////////////////////////////////////////////////
 
@@ -178,8 +189,10 @@
     led2=1;
 
     while(1) {
+        nh.spinOnce();      //ROS
         if(state==0) {
-            if(toggle) {
+            if(shot == 1) {
+                led3 = 1;
                 state++;
                 motor.reset();
                 setSpeed(THROW_SPEED);
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros_lib_melodic.lib	Sun Jul 25 13:58:43 2021 +0000
@@ -0,0 +1,1 @@
+https://os.mbed.com/teams/7th_DENSOU/code/ros_lib_melodic/#da82487f547e