added broadcaster for l.mouse
Dependencies: QEI mbed ros_lib_kinetic
Fork of Mouse_ISR_broadcaster by
main.cpp
- Committer:
- sreeraj
- Date:
- 2018-07-24
- Revision:
- 8:f118cc66e271
- Parent:
- 7:f71761cac14a
- Child:
- 9:e705f028f853
File content as of revision 8:f118cc66e271:
#include "mbed.h" #include "QEI.h" #include "ros.h" #include "ros/time.h" #include <tf/tf.h> #include <math.h> #include "geometry_msgs/Quaternion.h" #include <tf/transform_broadcaster.h> #include <nav_msgs/Odometry.h> #include "geometry_msgs/Vector3.h" #define ODOM_TICK_TOPIC "/odom_msg" #define ODOM_TOPIC "/odom" #define ODOM_FRAME "odom" #define BASE_FRAME "base_link" #define RADTODEG(angleInRadians) ((angleInRadians) * 180.0 / M_PI) ros::NodeHandle nh; //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); geometry_msgs::Quaternion wheelMsg; ros::Publisher wheelPub("/odom_msg", &wheelMsg); geometry_msgs::Vector3 odom_base; ros::Publisher odom_base_pub("/odom_base", &odom_base); //for odom_pub //geometry_msgs::Quaternion odom_quat; geometry_msgs::TransformStamped odom_trans; geometry_msgs::TransformStamped odom_trans2; struct OdomValues { double x; double y; double theta; OdomValues(double x, double y, double theta) { this->x = x; this->y = y; this->theta = theta; } }; nav_msgs::Odometry odomMsg; ros::Publisher odomPub("odom", &odomMsg); geometry_msgs::TransformStamped odomTransform; tf::TransformBroadcaster odomBroadcaster; geometry_msgs::TransformStamped odomTransform2; tf::TransformBroadcaster odomBroadcaster2; geometry_msgs::TransformStamped odomTransform3; tf::TransformBroadcaster odomBroadcaster3; OdomValues currentOdom(0.0, 0.0, 0.0); void publishOdometry(); //rosserial does not like volatile ints int leftPosX=0; int leftPosY=0; int rightPosX=0; int rightPosY=0; int main(){ nh.initNode(); nh.advertise(wheelPub); nh.advertise(odom_base_pub); nh.advertise(odomPub); odomBroadcaster.init(nh); odomBroadcaster2.init(nh); odomBroadcaster3.init(nh); // pc.baud(57600); while(true){ leftPosX = leftX.getPulses(); leftPosY = leftY.getPulses(); rightPosX = rightX.getPulses(); rightPosY = rightY.getPulses(); wheelMsg.x= leftPosX/10; wheelMsg.y = leftPosY/10; wheelMsg.z = rightPosX/10; wheelMsg.w = rightPosY/10; odom_base.x = (leftPosX+rightPosX)*0.05; odom_base.y=(leftPosY + rightPosY)*0.05; if(rightPosX- leftPosX !=0){ odom_base.z= atan(double(rightPosY-leftPosY)/double(rightPosX- leftPosX))*(180/3.14); } else{ odom_base.z=0.0; } odom_base_pub.publish(&odom_base); wheelPub.publish(&wheelMsg); publishOdometry(); nh.spinOnce(); wait(.08); } } void publishOdometry() { // Set initial header values odomTransform.header.stamp = nh.now(); odomTransform.header.frame_id = ODOM_FRAME; odomTransform.child_frame_id = "mouse1"; odomTransform2.header.stamp = nh.now(); odomTransform2.header.frame_id = ODOM_FRAME; odomTransform2.child_frame_id = "mouse2"; odomTransform3.header.stamp = nh.now(); odomTransform3.header.frame_id = ODOM_FRAME; odomTransform3.child_frame_id = "mouse_base"; odomMsg.header.stamp = odomTransform.header.stamp; odomMsg.header.frame_id = odomTransform.header.frame_id; odomMsg.child_frame_id = odomTransform.child_frame_id; geometry_msgs::Quaternion rotation = tf::createQuaternionFromYaw(currentOdom.theta); odomTransform.transform.translation.x = wheelMsg.x; odomTransform.transform.translation.y = wheelMsg.y; odomTransform.transform.translation.z = 0.0; odomTransform.transform.rotation = rotation; odomTransform2.transform.translation.x = wheelMsg.z; odomTransform2.transform.translation.y = wheelMsg.w; odomTransform2.transform.translation.z = 0.0; odomTransform2.transform.rotation = rotation; odomTransform3.transform.translation.x = odom_base.x; odomTransform3.transform.translation.y = odom_base.y; odomTransform3.transform.translation.z = 0.0; odomTransform3.transform.rotation = rotation; odomMsg.pose.pose.position.x = wheelMsg.x; odomMsg.pose.pose.position.y = wheelMsg.y; odomMsg.pose.pose.position.z = 0.0; odomMsg.pose.pose.orientation = rotation; // Publish result odomPub.publish(&odomMsg); odomBroadcaster.sendTransform(odomTransform); odomBroadcaster2.sendTransform(odomTransform2); odomBroadcaster3.sendTransform(odomTransform3); }