Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: QEI mbed ros_lib_kinetic
Fork of Mouse_ISR by
main.cpp
- Committer:
- apriljunio
- Date:
- 2018-07-23
- Revision:
- 5:e674692f6d15
- Parent:
- 4:f87a415beec4
File content as of revision 5:e674692f6d15:
#include "mbed.h"
#include "QEI.h"
#include "ros.h"
#include "geometry_msgs/Quaternion.h"
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
//PINA / PINB / INDEXPIN / PPR / ENCODING (X2 BY DEFAULT)
QEI leftX(D4, D5, NC, 378,QEI::X2_ENCODING);
QEI leftY(D10, D11, NC, 378,QEI::X2_ENCODING);
QEI rightX(D0, D1, NC, 378,QEI::X2_ENCODING);
QEI rightY(D2, D3, NC, 378,QEI::X2_ENCODING);
ros::NodeHandle nh;
geometry_msgs::Quaternion wheelMsg;
geometry_msgs::Quaternion odom_quat;
geometry_msgs::TransformStamped odom_trans;
tf::TransformBroadcaster odom_broadcaster;
ros::Publisher wheelPub("/odom_msg", &wheelMsg);
//rosserial does not like volatile ints
int leftPosX=0;
int leftPosY=0;
int rightPosX=0;
int rightPosY=0;
double theta=0;
ros::Time current_time;
int main(){
nh.initNode();
odom_broadcaster.init(nh);
//nh.advertise(chatter);
nh.advertise(wheelPub);
//nh.advertise(odom_quat);
// pc.baud(57600);
while(true){
current_time = nh.now();
leftPosX = leftX.getPulses();
leftPosY = leftY.getPulses();
rightPosX = rightX.getPulses();
rightPosY = rightY.getPulses();
wheelMsg.x= leftPosX;
wheelMsg.y = leftPosY;
wheelMsg.z = rightPosX;
wheelMsg.w = rightPosY;
odom_quat.x=0;
odom_quat.y=0;
odom_quat.z=0;
odom_quat.w=0;
odom_trans.header.stamp= current_time;
odom_trans.header.frame_id="world";
odom_trans.header.stamp = current_time;
odom_trans.child_frame_id = "base_link";
odom_trans.transform.translation.x = rightPosX;
odom_trans.transform.translation.y = rightPosY;
odom_trans.transform.translation.z = 0.0;
odom_trans.transform.rotation = odom_quat;
//send the transform
odom_broadcaster.sendTransform(odom_trans);
wheelPub.publish(&wheelMsg);
nh.spinOnce();
wait(1000);
}
}
