w/ ROSserial Publisher
Dependencies: QEI mbed ros_lib_kinetic
main.cpp@5:4eb9b5e03f02, 2018-07-23 (annotated)
- Committer:
- apriljunio
- Date:
- Mon Jul 23 15:19:32 2018 +0000
- Revision:
- 5:4eb9b5e03f02
- Parent:
- 1:7ba9803d4e01
Sorry
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
apriljunio | 0:1a95e3b1026a | 1 | #include "mbed.h" |
apriljunio | 0:1a95e3b1026a | 2 | #include "QEI.h" |
apriljunio | 0:1a95e3b1026a | 3 | #include "ros.h" |
apriljunio | 0:1a95e3b1026a | 4 | #include "geometry_msgs/Quaternion.h" |
apriljunio | 0:1a95e3b1026a | 5 | |
apriljunio | 0:1a95e3b1026a | 6 | //PINA / PINB / INDEXPIN / PPR / ENCODING (X2 BY DEFAULT) |
apriljunio | 5:4eb9b5e03f02 | 7 | QEI leftEncoder(D6, D7, NC, 378,QEI::X4_ENCODING); |
apriljunio | 5:4eb9b5e03f02 | 8 | QEI rightEncoder(D8, D9, NC, 378,QEI::X4_ENCODING); |
apriljunio | 0:1a95e3b1026a | 9 | |
apriljunio | 0:1a95e3b1026a | 10 | ros::NodeHandle nh; |
apriljunio | 0:1a95e3b1026a | 11 | geometry_msgs::Quaternion wheelMsg; |
apriljunio | 0:1a95e3b1026a | 12 | ros::Publisher wheelPub("/odom_msg", &wheelMsg); |
apriljunio | 0:1a95e3b1026a | 13 | |
apriljunio | 1:7ba9803d4e01 | 14 | //rosserial does not like volatile ints |
apriljunio | 0:1a95e3b1026a | 15 | int leftPulseA=0; |
apriljunio | 0:1a95e3b1026a | 16 | int rightPulseA=0; |
apriljunio | 0:1a95e3b1026a | 17 | |
apriljunio | 0:1a95e3b1026a | 18 | int main(){ |
apriljunio | 0:1a95e3b1026a | 19 | |
apriljunio | 0:1a95e3b1026a | 20 | nh.initNode(); |
apriljunio | 0:1a95e3b1026a | 21 | //nh.advertise(chatter); |
apriljunio | 0:1a95e3b1026a | 22 | nh.advertise(wheelPub); |
apriljunio | 5:4eb9b5e03f02 | 23 | // pc.baud(57600); |
apriljunio | 0:1a95e3b1026a | 24 | |
apriljunio | 0:1a95e3b1026a | 25 | while(true){ |
apriljunio | 0:1a95e3b1026a | 26 | |
apriljunio | 0:1a95e3b1026a | 27 | leftPulseA=leftEncoder.getPulses(); |
apriljunio | 0:1a95e3b1026a | 28 | rightPulseA = rightEncoder.getPulses(); |
apriljunio | 0:1a95e3b1026a | 29 | |
apriljunio | 0:1a95e3b1026a | 30 | wheelMsg.x= leftPulseA; |
apriljunio | 5:4eb9b5e03f02 | 31 | wheelMsg.y = rightPulseA;//timeL; |
apriljunio | 5:4eb9b5e03f02 | 32 | wheelMsg.z = 0.0; |
apriljunio | 1:7ba9803d4e01 | 33 | wheelMsg.w = 0.0;//timeR; |
apriljunio | 0:1a95e3b1026a | 34 | |
apriljunio | 0:1a95e3b1026a | 35 | wheelPub.publish(&wheelMsg); |
apriljunio | 0:1a95e3b1026a | 36 | nh.spinOnce(); |
apriljunio | 0:1a95e3b1026a | 37 | wait(0.01); |
apriljunio | 0:1a95e3b1026a | 38 | } |
apriljunio | 0:1a95e3b1026a | 39 | } |