35 #include <tf/transform_broadcaster.h>
36 #include <nav_msgs/Odometry.h>
38 #define DEFAULT_WHEEL_BASE 0.497
42 #include <atlasmv_base/AtlasmvStatus.h>
59 int main(
int argc,
char** argv)
61 ros::init(argc, argv,
"atlasmv_egomotion");
64 ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>(
"/atlasmv/base/odometry", 50);
65 tf::TransformBroadcaster odom_broadcaster;
67 Subscriber subscribeStatusMessages = n.subscribe (
"/atlasmv/base/status", 1,
StatusMessageHandler);
84 ros::Time current_time, last_time;
85 current_time = ros::Time::now();
86 last_time = ros::Time::now();
90 ROS_INFO(
"Starting to spin ...");
102 current_time = ros::Time::now();
108 double dt = (current_time - last_time).toSec();
114 delta_x=cos(th)*cos(phi)*vl*dt;
115 delta_y=sin(th)*cos(phi)*vl*dt;
116 delta_th=sin(phi/l)*vl*dt;
118 ROS_INFO(
"cos(th):%f,cos(phi):%f",cos(th),cos(phi));
119 ROS_INFO(
"dx:%f,dy:%f,dth:%f",delta_x,delta_y,delta_th);
120 ROS_INFO(
"th:%f,phi:%f,vl:%f",th,phi,vl);
130 ROS_INFO(
"dt:%f",dt);
131 ROS_INFO(
"x:%f,y:%f,th:%f",x,y,th);
132 ROS_INFO(
"vx:%f,vy:%f,vth:%f",vx,vy,vth);
135 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
138 geometry_msgs::TransformStamped odom_trans;
139 odom_trans.header.stamp = current_time;
140 odom_trans.header.frame_id =
"/odom";
141 odom_trans.child_frame_id =
"/base_link";
143 odom_trans.transform.translation.x = x;
144 odom_trans.transform.translation.y = y;
145 odom_trans.transform.translation.z = 0.0;
146 odom_trans.transform.rotation = odom_quat;
149 odom_broadcaster.sendTransform(odom_trans);
152 nav_msgs::Odometry odom;
153 odom.header.stamp = current_time;
154 odom.header.frame_id =
"/odom";
157 odom.pose.pose.position.x = x;
158 odom.pose.pose.position.y = y;
161 odom.pose.pose.position.z = 0.0;
162 odom.pose.pose.orientation = odom_quat;
165 odom.child_frame_id =
"/base_link";
166 odom.twist.twist.linear.x = vx;
167 odom.twist.twist.linear.y = vy;
168 odom.twist.twist.angular.z = vth;
171 odom_pub.publish(odom);
173 last_time = current_time;
void StatusMessageHandler(const atlasmv_base::AtlasmvStatus &msg)
void IncommingDataHandler(int)
bool ConvertEstimatedToMeasurment(double vl, double dir, double *dx, double *dy, double *dtheta, double dt, double l, double bwa)
#define DEFAULT_WHEEL_BASE
atlasmv_base::AtlasmvStatus base_status
int main(int argc, char **argv)