added broadcaster for l.mouse
Dependencies: QEI mbed ros_lib_kinetic
Fork of Mouse_ISR_broadcaster by
main.cpp@2:47663f3fec3a, 2018-07-19 (annotated)
- Committer:
- apriljunio
- Date:
- Thu Jul 19 20:12:47 2018 +0000
- Revision:
- 2:47663f3fec3a
- Parent:
- 1:7ba9803d4e01
- Child:
- 3:ab392a9f941d
Odometry using Mice
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 | 2:47663f3fec3a | 7 | QEI leftX(D6, D7, NC, 378,QEI::X2_ENCODING); |
apriljunio | 2:47663f3fec3a | 8 | QEI leftY(D8, D9, NC, 378,QEI::X2_ENCODING); |
apriljunio | 2:47663f3fec3a | 9 | QEI rightX(D0, D1, NC, 378,QEI::X2_ENCODING); |
apriljunio | 2:47663f3fec3a | 10 | QEI rightY(D2, D3, NC, 378,QEI::X2_ENCODING); |
apriljunio | 0:1a95e3b1026a | 11 | |
apriljunio | 0:1a95e3b1026a | 12 | ros::NodeHandle nh; |
apriljunio | 0:1a95e3b1026a | 13 | geometry_msgs::Quaternion wheelMsg; |
apriljunio | 0:1a95e3b1026a | 14 | ros::Publisher wheelPub("/odom_msg", &wheelMsg); |
apriljunio | 0:1a95e3b1026a | 15 | |
apriljunio | 1:7ba9803d4e01 | 16 | //rosserial does not like volatile ints |
apriljunio | 2:47663f3fec3a | 17 | int leftPosX=0; |
apriljunio | 2:47663f3fec3a | 18 | int leftPosY=0; |
apriljunio | 2:47663f3fec3a | 19 | int rightPosX=0; |
apriljunio | 2:47663f3fec3a | 20 | int rightPosY=0; |
apriljunio | 0:1a95e3b1026a | 21 | |
apriljunio | 0:1a95e3b1026a | 22 | int main(){ |
apriljunio | 0:1a95e3b1026a | 23 | |
apriljunio | 0:1a95e3b1026a | 24 | nh.initNode(); |
apriljunio | 0:1a95e3b1026a | 25 | //nh.advertise(chatter); |
apriljunio | 0:1a95e3b1026a | 26 | nh.advertise(wheelPub); |
apriljunio | 2:47663f3fec3a | 27 | // pc.baud(57600); |
apriljunio | 0:1a95e3b1026a | 28 | |
apriljunio | 0:1a95e3b1026a | 29 | while(true){ |
apriljunio | 0:1a95e3b1026a | 30 | |
apriljunio | 2:47663f3fec3a | 31 | leftPosX = leftX.getPulses(); |
apriljunio | 2:47663f3fec3a | 32 | leftPosY = leftY.getPulses(); |
apriljunio | 2:47663f3fec3a | 33 | rightPosX = rightX.getPulses(); |
apriljunio | 2:47663f3fec3a | 34 | rightPosY = rightY.getPulses(); |
apriljunio | 0:1a95e3b1026a | 35 | |
apriljunio | 2:47663f3fec3a | 36 | wheelMsg.x= leftPosX; |
apriljunio | 2:47663f3fec3a | 37 | wheelMsg.y = leftPosY; |
apriljunio | 2:47663f3fec3a | 38 | wheelMsg.z = rightPosX; |
apriljunio | 2:47663f3fec3a | 39 | wheelMsg.w = rightPosY; |
apriljunio | 0:1a95e3b1026a | 40 | |
apriljunio | 0:1a95e3b1026a | 41 | wheelPub.publish(&wheelMsg); |
apriljunio | 0:1a95e3b1026a | 42 | nh.spinOnce(); |
apriljunio | 0:1a95e3b1026a | 43 | wait(0.01); |
apriljunio | 0:1a95e3b1026a | 44 | } |
apriljunio | 0:1a95e3b1026a | 45 | } |