Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <ros/ros.h>
00037 #include <geometry_msgs/Twist.h>
00038 #include <dbw_mkz_msgs/TwistCmd.h>
00039
00040
00041 #include <dynamic_reconfigure/server.h>
00042 #include <dbw_mkz_twist_controller/TwistTestConfig.h>
00043
00044
00045 dbw_mkz_twist_controller::TwistTestConfig cfg_;
00046 ros::Publisher pub_twist, pub_twist2;
00047
00048
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
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
00102 dynamic_reconfigure::Server<dbw_mkz_twist_controller::TwistTestConfig> srv;
00103 srv.setCallback(boost::bind(reconfig, _1, _2));
00104
00105
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
00110 ros::Timer timer = n.createTimer(ros::Duration(1/20.0), timerCallback);
00111
00112
00113 ros::spin();
00114
00115 return 0;
00116 }
00117