37 #include <geometry_msgs/Twist.h> 38 #include <dbw_mkz_msgs/TwistCmd.h> 41 #include <dynamic_reconfigure/server.h> 42 #include <dbw_mkz_twist_controller/TwistTestConfig.h> 45 dbw_mkz_twist_controller::TwistTestConfig
cfg_;
49 static double mphToMps(
double mph) {
return mph * 0.44704; }
50 static double kphToMps(
double kph) {
return kph * 0.277778; }
52 return radius != 0.0 ? speed / radius : 0.0;
56 void reconfig(dbw_mkz_twist_controller::TwistTestConfig& config, uint32_t level)
64 dbw_mkz_msgs::TwistCmd cmd;
65 switch (
cfg_.speed_units) {
67 case dbw_mkz_twist_controller::TwistTest_SPEED_MPS:
68 cmd.twist.linear.x =
cfg_.speed;
70 case dbw_mkz_twist_controller::TwistTest_SPEED_MPH:
73 case dbw_mkz_twist_controller::TwistTest_SPEED_KPH:
77 switch (
cfg_.yaw_method) {
79 case dbw_mkz_twist_controller::TwistTest_YAW_RATE:
80 cmd.twist.angular.z =
cfg_.yaw_rate;
82 case dbw_mkz_twist_controller::TwistTest_YAW_RADIUS:
86 if (
cfg_.use_limits) {
87 cmd.accel_limit =
cfg_.accel_max;
88 cmd.decel_limit =
cfg_.decel_max;
96 int main(
int argc,
char** argv)
102 dynamic_reconfigure::Server<dbw_mkz_twist_controller::TwistTestConfig> srv;
103 srv.setCallback(boost::bind(
reconfig, _1, _2));
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);
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)
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)
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)