twist_tester.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015-2018, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 // ROS and messages
00036 #include <ros/ros.h>
00037 #include <geometry_msgs/Twist.h>
00038 #include <dbw_mkz_msgs/TwistCmd.h>
00039 
00040 // Dynamic Reconfigure
00041 #include <dynamic_reconfigure/server.h>
00042 #include <dbw_mkz_twist_controller/TwistTestConfig.h>
00043 
00044 // Global variables
00045 dbw_mkz_twist_controller::TwistTestConfig cfg_;
00046 ros::Publisher pub_twist, pub_twist2;
00047 
00048 // Static functions
00049 static double mphToMps(double mph) { return mph * 0.44704; }
00050 static double kphToMps(double kph) { return kph * 0.277778; }
00051 static double yawRateFromRadius(double speed, double radius) {
00052   return radius != 0.0 ? speed / radius : 0.0;
00053 }
00054 
00055 // Dynamic Reconfigure callback
00056 void reconfig(dbw_mkz_twist_controller::TwistTestConfig& config, uint32_t level)
00057 {
00058   cfg_ = config;
00059 }
00060 
00061 void timerCallback(const ros::TimerEvent& event)
00062 {
00063   if (cfg_.publish) {
00064     dbw_mkz_msgs::TwistCmd cmd;
00065     switch (cfg_.speed_units) {
00066       default:
00067       case dbw_mkz_twist_controller::TwistTest_SPEED_MPS:
00068         cmd.twist.linear.x = cfg_.speed;
00069         break;
00070       case dbw_mkz_twist_controller::TwistTest_SPEED_MPH:
00071         cmd.twist.linear.x = mphToMps(cfg_.speed);
00072         break;
00073       case dbw_mkz_twist_controller::TwistTest_SPEED_KPH:
00074         cmd.twist.linear.x = kphToMps(cfg_.speed);
00075         break;
00076     }
00077     switch (cfg_.yaw_method) {
00078       default:
00079       case dbw_mkz_twist_controller::TwistTest_YAW_RATE:
00080         cmd.twist.angular.z = cfg_.yaw_rate;
00081         break;
00082       case dbw_mkz_twist_controller::TwistTest_YAW_RADIUS:
00083         cmd.twist.angular.z = yawRateFromRadius(cmd.twist.linear.x, cfg_.yaw_radius);
00084         break;
00085     }
00086     if (cfg_.use_limits) {
00087       cmd.accel_limit = cfg_.accel_max;
00088       cmd.decel_limit = cfg_.decel_max;
00089       pub_twist2.publish(cmd);
00090     } else {
00091       pub_twist.publish(cmd.twist);
00092     }
00093   }
00094 }
00095 
00096 int main(int argc, char** argv)
00097 {
00098   ros::init(argc, argv, "twist_tester");
00099   ros::NodeHandle n;
00100 
00101   // Dynamic Reconfigure
00102   dynamic_reconfigure::Server<dbw_mkz_twist_controller::TwistTestConfig> srv;
00103   srv.setCallback(boost::bind(reconfig, _1, _2));
00104 
00105   // Publishers
00106   pub_twist = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00107   pub_twist2 = n.advertise<dbw_mkz_msgs::TwistCmd>("cmd_vel_with_limits", 1);
00108 
00109   // Timer
00110   ros::Timer timer = n.createTimer(ros::Duration(1/20.0), timerCallback);
00111 
00112   // Handle callbacks
00113   ros::spin();
00114 
00115   return 0;
00116 }
00117 


dbw_mkz_twist_controller
Author(s): Micho Radovnikovich , Kevin Hallenbeck
autogenerated on Thu Jul 4 2019 20:08:22