VNH ROSSERIAL PUB+SUB
Dependencies: Motordriver QEI mbed ros_lib_kinetic
Fork of Test by
main.cpp@1:5f2cb6bc0a8e, 2018-07-13 (annotated)
- Committer:
- apriljunio
- Date:
- Fri Jul 13 20:35:51 2018 +0000
- Revision:
- 1:5f2cb6bc0a8e
- Parent:
- 0:99538487421b
- Child:
- 2:82249618b6bc
No ramps;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
apriljunio | 0:99538487421b | 1 | #include "mbed.h" |
apriljunio | 0:99538487421b | 2 | #include "motordriver.h" |
apriljunio | 0:99538487421b | 3 | #include "ros.h" |
apriljunio | 0:99538487421b | 4 | #include "geometry_msgs/Vector3.h" |
apriljunio | 0:99538487421b | 5 | |
apriljunio | 0:99538487421b | 6 | //pwm, fwd, rev, can brake |
apriljunio | 0:99538487421b | 7 | Motor motorLeft(D9,D5,D4, 1); |
apriljunio | 0:99538487421b | 8 | Motor motorRight(D10, D7, D8, 1); |
apriljunio | 0:99538487421b | 9 | |
apriljunio | 0:99538487421b | 10 | ros:: NodeHandle nh; |
apriljunio | 0:99538487421b | 11 | |
apriljunio | 0:99538487421b | 12 | void messageCb( const geometry_msgs::Vector3& msg) |
apriljunio | 0:99538487421b | 13 | { |
apriljunio | 1:5f2cb6bc0a8e | 14 | //while (true) { |
apriljunio | 1:5f2cb6bc0a8e | 15 | //for (float s=-msg.x; s < msg.x ; s += 0.01f) { |
apriljunio | 1:5f2cb6bc0a8e | 16 | motorLeft.speed(msg.x); |
apriljunio | 1:5f2cb6bc0a8e | 17 | motorRight.speed(msg.y); |
apriljunio | 1:5f2cb6bc0a8e | 18 | // wait(0.005);} |
apriljunio | 1:5f2cb6bc0a8e | 19 | // } |
apriljunio | 0:99538487421b | 20 | } |
apriljunio | 0:99538487421b | 21 | |
apriljunio | 0:99538487421b | 22 | ros::Subscriber<geometry_msgs::Vector3> sub("/motor/command", &messageCb ); |
apriljunio | 0:99538487421b | 23 | |
apriljunio | 0:99538487421b | 24 | int main() { |
apriljunio | 0:99538487421b | 25 | |
apriljunio | 0:99538487421b | 26 | nh.initNode(); |
apriljunio | 0:99538487421b | 27 | nh.subscribe(sub); |
apriljunio | 0:99538487421b | 28 | |
apriljunio | 0:99538487421b | 29 | while (true) { |
apriljunio | 0:99538487421b | 30 | nh.spinOnce(); |
apriljunio | 0:99538487421b | 31 | wait_ms(1); |
apriljunio | 0:99538487421b | 32 | } |
apriljunio | 0:99538487421b | 33 | } |
apriljunio | 0:99538487421b | 34 |