25 #include "geometry_msgs/Twist.h"
27 #include "sensor_msgs/Joy.h"
44 void joyCallback(
const sensor_msgs::Joy::ConstPtr& joy);
45 void sendCmdVelMsg(
const sensor_msgs::Joy::ConstPtr& joy_msg,
const std::string& which_map);
98 nh_param->
param<
double>(
"scale_angular_turbo",
109 ROS_INFO_NAMED(
"TeleopTwistJoy",
"Linear axis %s on %i at scale %f.",
112 "Turbo for linear axis %s is scale %f.", it->first.c_str(),
pimpl_->
scale_linear_map[
"turbo"][it->first]);
118 ROS_INFO_NAMED(
"TeleopTwistJoy",
"Angular axis %s on %i at scale %f.",
127 double getVal(
const sensor_msgs::Joy::ConstPtr& joy_msg,
const std::map<std::string, int>& axis_map,
128 const std::map<std::string, double>& scale_map,
const std::string& fieldname)
130 if (axis_map.find(fieldname) == axis_map.end() ||
131 scale_map.find(fieldname) == scale_map.end() ||
132 joy_msg->axes.size() <= axis_map.at(fieldname))
137 return joy_msg->axes[axis_map.at(fieldname)] * scale_map.at(fieldname);
141 const std::string& which_map)
144 geometry_msgs::Twist cmd_vel_msg;
159 if (enable_turbo_button >= 0 &&
160 joy_msg->buttons.size() > enable_turbo_button &&
161 joy_msg->buttons[enable_turbo_button])
163 sendCmdVelMsg(joy_msg,
"turbo");
165 else if (joy_msg->buttons.size() > enable_button &&
166 joy_msg->buttons[enable_button])
168 sendCmdVelMsg(joy_msg,
"normal");
174 if (!sent_disable_msg)
177 geometry_msgs::Twist cmd_vel_msg;
178 cmd_vel_pub.publish(cmd_vel_msg);
179 sent_disable_msg =
true;