w/ ROSserial Publisher
Dependencies: QEI mbed ros_lib_kinetic
Revision 5:4eb9b5e03f02, committed 2018-07-23
- Comitter:
- apriljunio
- Date:
- Mon Jul 23 15:19:32 2018 +0000
- Parent:
- 1:7ba9803d4e01
- Commit message:
- Sorry
Changed in this revision
main.cpp | Show annotated file Show diff for this revision Revisions of this file |
--- a/main.cpp Mon Jul 16 19:47:46 2018 +0000 +++ b/main.cpp Mon Jul 23 15:19:32 2018 +0000 @@ -4,8 +4,8 @@ #include "geometry_msgs/Quaternion.h" //PINA / PINB / INDEXPIN / PPR / ENCODING (X2 BY DEFAULT) -QEI leftEncoder(D3, D12, NC, 378); -QEI rightEncoder(D2, D13, NC, 378); +QEI leftEncoder(D6, D7, NC, 378,QEI::X4_ENCODING); +QEI rightEncoder(D8, D9, NC, 378,QEI::X4_ENCODING); ros::NodeHandle nh; geometry_msgs::Quaternion wheelMsg; @@ -15,35 +15,23 @@ int leftPulseA=0; int rightPulseA=0; -//timeL; -//timeR; - int main(){ nh.initNode(); //nh.advertise(chatter); nh.advertise(wheelPub); - // pc.baud(57600); - + // pc.baud(57600); while(true){ leftPulseA=leftEncoder.getPulses(); rightPulseA = rightEncoder.getPulses(); - //timeL = tL.read(); - //timeR = tL.read(); wheelMsg.x= leftPulseA; - wheelMsg.y = 0.0;//timeL; - wheelMsg.z = rightPulseA; + wheelMsg.y = rightPulseA;//timeL; + wheelMsg.z = 0.0; wheelMsg.w = 0.0;//timeR; - - //pc.printf("Left pulses %i \n", leftPulseA); - //pc.printf("Right pulses %i \n", rightPulseA); - - //str_msg.data=hello; - //chatter.publish(&str_msg); wheelPub.publish(&wheelMsg); nh.spinOnce(); wait(0.01);