15 #include <geometry_msgs/Twist.h>
18 #define MOTORSHIELD_IN1 p21
19 #define MOTORSHIELD_IN2 p22
20 #define MOTORSHIELD_IN3 p23
21 #define MOTORSHIELD_IN4 p24
22 #define SPEEDPIN_A p25
23 #define SPEEDPIN_B p26
24 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
25 #define MOTORSHIELD_IN1 D8
26 #define MOTORSHIELD_IN2 D11
27 #define MOTORSHIELD_IN3 D12
28 #define MOTORSHIELD_IN4 D13
30 #define SPEEDPIN_B D10
32 #error "You need to specify a pin for the sensor"
35 MotorDriver motorDriver(MOTORSHIELD_IN1, MOTORSHIELD_IN2, MOTORSHIELD_IN3, MOTORSHIELD_IN4, SPEEDPIN_A, SPEEDPIN_B);
40 if (msg.angular.z == 0 && msg.linear.x == 0)
46 if (msg.angular.z < 0)
48 int speed = (int)(msg.angular.z * -100);
53 else if (msg.angular.z > 0)
55 int speed = (int)(msg.angular.z * 100);
60 else if (msg.linear.x < 0)
62 int speed = (int)(msg.linear.x * -100);
67 else if (msg.linear.x > 0)
69 int speed = (int)(msg.linear.x * 100);
91 if (
t.read_ms() > vel_timer)
94 vel_timer =
t.read_ms() + 500;