atlasmv_egomotion.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include <iostream>
33 #include <ros/ros.h>
34 
35 #include <tf/transform_broadcaster.h>
36 #include <nav_msgs/Odometry.h>
37 
38 #define DEFAULT_WHEEL_BASE 0.497
39 
40 #include <signal.h>
41 
42 #include <atlasmv_base/AtlasmvStatus.h>
43 
44 using namespace ros;
45 using namespace std;
46 
47 void IncommingDataHandler(int);
48 bool ConvertEstimatedToMeasurment(double vl,double dir,double*dx,double*dy,double*dtheta,double dt,double l,double bwa);
49 
51 atlasmv_base::AtlasmvStatus base_status;
52 
53 void StatusMessageHandler(const atlasmv_base::AtlasmvStatus& msg)
54 {
55  base_status=msg;
56  new_status_message=true;
57 }
58 
59 int main(int argc, char** argv)
60 {
61  ros::init(argc, argv, "atlasmv_egomotion");
62 
63  ros::NodeHandle n;
64  ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("/atlasmv/base/odometry", 50); // atmv??
65  tf::TransformBroadcaster odom_broadcaster;
66 
67  Subscriber subscribeStatusMessages = n.subscribe ("/atlasmv/base/status", 1, StatusMessageHandler); // atmv??
68 
69  double x = 0.0;
70  double y = 0.0;
71  double th = 0.0;
72 
73  double vx = 0.0;
74  double vy = 0.0;
75  double vth = 0.0;
76 
77  double vl,phi;
78  double l;
79 
80  n.param("wheel_base",l,DEFAULT_WHEEL_BASE);
81 
82  new_status_message=false;
83 
84  ros::Time current_time, last_time;
85  current_time = ros::Time::now();
86  last_time = ros::Time::now();
87 
88  ros::Rate r(60.0);
89 
90  ROS_INFO("Starting to spin ...");
91 
92  while(n.ok())
93  {
94  spinOnce();
95  r.sleep();
96 
98  continue;
99 
100  new_status_message=false;
101 
102  current_time = ros::Time::now();
103 
104  vl=base_status.speed;
105  phi=base_status.dir;
106 
107  //compute odometry
108  double dt = (current_time - last_time).toSec();
109 
110  double delta_x;
111  double delta_y;
112  double delta_th;
113 
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;
117 
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);
121 
122  vx = delta_x/dt;
123  vy = delta_y/dt;
124  vth = delta_th/dt;
125 
126  x += delta_x;
127  y += delta_y;
128  th += delta_th;
129 
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);
133 
134  //since all odometry is 6DOF we'll need a quaternion created from yaw
135  geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
136 
137  //first, we'll publish the transform over tf
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";
142 
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;
147 
148  //send the transform
149  odom_broadcaster.sendTransform(odom_trans);
150 
151  //next, we'll publish the odometry message over ROS
152  nav_msgs::Odometry odom;
153  odom.header.stamp = current_time;
154  odom.header.frame_id = "/odom";
155 
156  //set the position
157  odom.pose.pose.position.x = x;
158  odom.pose.pose.position.y = y;
159 
160 
161  odom.pose.pose.position.z = 0.0;
162  odom.pose.pose.orientation = odom_quat;
163 
164  //set the velocity
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;
169 
170  //publish the message
171  odom_pub.publish(odom);
172 
173  last_time = current_time;
174  }
175 }
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
double dir
Definition: atlasmv.h:182
int main(int argc, char **argv)
bool new_status_message


atlasmv_base
Author(s): David Gameiro, Jorge Almeida
autogenerated on Mon Mar 2 2015 01:31:28