twist_tester.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-2018, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 // ROS and messages
36 #include <ros/ros.h>
37 #include <geometry_msgs/Twist.h>
38 #include <dbw_mkz_msgs/TwistCmd.h>
39 
40 // Dynamic Reconfigure
41 #include <dynamic_reconfigure/server.h>
42 #include <dbw_mkz_twist_controller/TwistTestConfig.h>
43 
44 // Global variables
45 dbw_mkz_twist_controller::TwistTestConfig cfg_;
47 
48 // Static functions
49 static double mphToMps(double mph) { return mph * 0.44704; }
50 static double kphToMps(double kph) { return kph * 0.277778; }
51 static double yawRateFromRadius(double speed, double radius) {
52  return radius != 0.0 ? speed / radius : 0.0;
53 }
54 
55 // Dynamic Reconfigure callback
56 void reconfig(dbw_mkz_twist_controller::TwistTestConfig& config, uint32_t level)
57 {
58  cfg_ = config;
59 }
60 
61 void timerCallback(const ros::TimerEvent& event)
62 {
63  if (cfg_.publish) {
64  dbw_mkz_msgs::TwistCmd cmd;
65  switch (cfg_.speed_units) {
66  default:
67  case dbw_mkz_twist_controller::TwistTest_SPEED_MPS:
68  cmd.twist.linear.x = cfg_.speed;
69  break;
70  case dbw_mkz_twist_controller::TwistTest_SPEED_MPH:
71  cmd.twist.linear.x = mphToMps(cfg_.speed);
72  break;
73  case dbw_mkz_twist_controller::TwistTest_SPEED_KPH:
74  cmd.twist.linear.x = kphToMps(cfg_.speed);
75  break;
76  }
77  switch (cfg_.yaw_method) {
78  default:
79  case dbw_mkz_twist_controller::TwistTest_YAW_RATE:
80  cmd.twist.angular.z = cfg_.yaw_rate;
81  break;
82  case dbw_mkz_twist_controller::TwistTest_YAW_RADIUS:
83  cmd.twist.angular.z = yawRateFromRadius(cmd.twist.linear.x, cfg_.yaw_radius);
84  break;
85  }
86  if (cfg_.use_limits) {
87  cmd.accel_limit = cfg_.accel_max;
88  cmd.decel_limit = cfg_.decel_max;
89  pub_twist2.publish(cmd);
90  } else {
91  pub_twist.publish(cmd.twist);
92  }
93  }
94 }
95 
96 int main(int argc, char** argv)
97 {
98  ros::init(argc, argv, "twist_tester");
100 
101  // Dynamic Reconfigure
102  dynamic_reconfigure::Server<dbw_mkz_twist_controller::TwistTestConfig> srv;
103  srv.setCallback(boost::bind(reconfig, _1, _2));
104 
105  // Publishers
106  pub_twist = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
107  pub_twist2 = n.advertise<dbw_mkz_msgs::TwistCmd>("cmd_vel_with_limits", 1);
108 
109  // Timer
111 
112  // Handle callbacks
113  ros::spin();
114 
115  return 0;
116 }
117 
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
dbw_mkz_twist_controller::TwistTestConfig cfg_
ros::Publisher pub_twist2
static double mphToMps(double mph)
ros::Publisher pub_twist
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
static double kphToMps(double kph)
static double yawRateFromRadius(double speed, double radius)
int main(int argc, char **argv)
void timerCallback(const ros::TimerEvent &event)
void reconfig(dbw_mkz_twist_controller::TwistTestConfig &config, uint32_t level)


dbw_mkz_twist_controller
Author(s): Micho Radovnikovich , Kevin Hallenbeck
autogenerated on Thu Nov 14 2019 03:46:10