dead_reckoning_node.cpp
Go to the documentation of this file.
00001 
00026 #include "ros/ros.h"
00027 #include "grizzly_motion/dead_reckoning.h"
00028 
00029 void encodersCallback(DeadReckoning* dr, ros::Publisher* pub, const grizzly_msgs::DriveConstPtr encoders)
00030 {
00031   nav_msgs::Odometry odom;
00032   if (dr->next(encoders, &odom)) {
00033     pub->publish(odom);
00034   }
00035 }
00036 
00040 int main(int argc, char ** argv)
00041 {
00042   double vehicle_width, wheel_radius;
00043 
00044   ros::init(argc, argv, "grizzly_dead_reckoning"); 
00045   ros::param::get("vehicle_width", vehicle_width);
00046   ros::param::get("wheel_radius", wheel_radius);
00047 
00048   DeadReckoning dr(vehicle_width, wheel_radius);
00049   ros::NodeHandle nh("");
00050   ros::Publisher pub(nh.advertise<nav_msgs::Odometry>("odom", 1));
00051   ros::Subscriber sub(nh.subscribe<grizzly_msgs::Drive>("motors/encoders", 1, boost::bind(
00052     encodersCallback, &dr, &pub, _1)));
00053 
00054   ros::spin();
00055 }


grizzly_motion
Author(s):
autogenerated on Fri Aug 28 2015 10:55:30