teleop_twist_joy.cpp
Go to the documentation of this file.
1 
25 #include "geometry_msgs/Twist.h"
26 #include "ros/ros.h"
27 #include "sensor_msgs/Joy.h"
29 
30 #include <map>
31 #include <string>
32 
33 
34 namespace teleop_twist_joy
35 {
36 
43 {
44  void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
45  void sendCmdVelMsg(const sensor_msgs::Joy::ConstPtr& joy_msg, const std::string& which_map);
46 
49 
52 
53  std::map<std::string, int> axis_linear_map;
54  std::map< std::string, std::map<std::string, double> > scale_linear_map;
55 
56  std::map<std::string, int> axis_angular_map;
57  std::map< std::string, std::map<std::string, double> > scale_angular_map;
58 
60 };
61 
68 {
69  pimpl_ = new Impl;
70 
71  pimpl_->cmd_vel_pub = nh->advertise<geometry_msgs::Twist>("cmd_vel", 1, true);
72  pimpl_->joy_sub = nh->subscribe<sensor_msgs::Joy>("joy", 1, &TeleopTwistJoy::Impl::joyCallback, pimpl_);
73 
74  nh_param->param<int>("enable_button", pimpl_->enable_button, 0);
75  nh_param->param<int>("enable_turbo_button", pimpl_->enable_turbo_button, -1);
76 
77  if (nh_param->getParam("axis_linear", pimpl_->axis_linear_map))
78  {
79  nh_param->getParam("scale_linear", pimpl_->scale_linear_map["normal"]);
80  nh_param->getParam("scale_linear_turbo", pimpl_->scale_linear_map["turbo"]);
81  }
82  else
83  {
84  nh_param->param<int>("axis_linear", pimpl_->axis_linear_map["x"], 1);
85  nh_param->param<double>("scale_linear", pimpl_->scale_linear_map["normal"]["x"], 0.5);
86  nh_param->param<double>("scale_linear_turbo", pimpl_->scale_linear_map["turbo"]["x"], 1.0);
87  }
88 
89  if (nh_param->getParam("axis_angular", pimpl_->axis_angular_map))
90  {
91  nh_param->getParam("scale_angular", pimpl_->scale_angular_map["normal"]);
92  nh_param->getParam("scale_angular_turbo", pimpl_->scale_angular_map["turbo"]);
93  }
94  else
95  {
96  nh_param->param<int>("axis_angular", pimpl_->axis_angular_map["yaw"], 0);
97  nh_param->param<double>("scale_angular", pimpl_->scale_angular_map["normal"]["yaw"], 0.5);
98  nh_param->param<double>("scale_angular_turbo",
99  pimpl_->scale_angular_map["turbo"]["yaw"], pimpl_->scale_angular_map["normal"]["yaw"]);
100  }
101 
102  ROS_INFO_NAMED("TeleopTwistJoy", "Teleop enable button %i.", pimpl_->enable_button);
103  ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
104  "Turbo on button %i.", pimpl_->enable_turbo_button);
105 
106  for (std::map<std::string, int>::iterator it = pimpl_->axis_linear_map.begin();
107  it != pimpl_->axis_linear_map.end(); ++it)
108  {
109  ROS_INFO_NAMED("TeleopTwistJoy", "Linear axis %s on %i at scale %f.",
110  it->first.c_str(), it->second, pimpl_->scale_linear_map["normal"][it->first]);
111  ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
112  "Turbo for linear axis %s is scale %f.", it->first.c_str(), pimpl_->scale_linear_map["turbo"][it->first]);
113  }
114 
115  for (std::map<std::string, int>::iterator it = pimpl_->axis_angular_map.begin();
116  it != pimpl_->axis_angular_map.end(); ++it)
117  {
118  ROS_INFO_NAMED("TeleopTwistJoy", "Angular axis %s on %i at scale %f.",
119  it->first.c_str(), it->second, pimpl_->scale_angular_map["normal"][it->first]);
120  ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
121  "Turbo for angular axis %s is scale %f.", it->first.c_str(), pimpl_->scale_angular_map["turbo"][it->first]);
122  }
123 
124  pimpl_->sent_disable_msg = false;
125 }
126 
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)
129 {
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))
133  {
134  return 0.0;
135  }
136 
137  return joy_msg->axes[axis_map.at(fieldname)] * scale_map.at(fieldname);
138 }
139 
140 void TeleopTwistJoy::Impl::sendCmdVelMsg(const sensor_msgs::Joy::ConstPtr& joy_msg,
141  const std::string& which_map)
142 {
143  // Initializes with zeros by default.
144  geometry_msgs::Twist cmd_vel_msg;
145 
146  cmd_vel_msg.linear.x = getVal(joy_msg, axis_linear_map, scale_linear_map[which_map], "x");
147  cmd_vel_msg.linear.y = getVal(joy_msg, axis_linear_map, scale_linear_map[which_map], "y");
148  cmd_vel_msg.linear.z = getVal(joy_msg, axis_linear_map, scale_linear_map[which_map], "z");
149  cmd_vel_msg.angular.z = getVal(joy_msg, axis_angular_map, scale_angular_map[which_map], "yaw");
150  cmd_vel_msg.angular.y = getVal(joy_msg, axis_angular_map, scale_angular_map[which_map], "pitch");
151  cmd_vel_msg.angular.x = getVal(joy_msg, axis_angular_map, scale_angular_map[which_map], "roll");
152 
153  cmd_vel_pub.publish(cmd_vel_msg);
154  sent_disable_msg = false;
155 }
156 
157 void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg)
158 {
159  if (enable_turbo_button >= 0 &&
160  joy_msg->buttons.size() > enable_turbo_button &&
161  joy_msg->buttons[enable_turbo_button])
162  {
163  sendCmdVelMsg(joy_msg, "turbo");
164  }
165  else if (joy_msg->buttons.size() > enable_button &&
166  joy_msg->buttons[enable_button])
167  {
168  sendCmdVelMsg(joy_msg, "normal");
169  }
170  else
171  {
172  // When enable button is released, immediately send a single no-motion command
173  // in order to stop the robot.
174  if (!sent_disable_msg)
175  {
176  // Initializes with zeros by default.
177  geometry_msgs::Twist cmd_vel_msg;
178  cmd_vel_pub.publish(cmd_vel_msg);
179  sent_disable_msg = true;
180  }
181  }
182 }
183 
184 } // namespace teleop_twist_joy
ros::Publisher
teleop_twist_joy::TeleopTwistJoy::Impl::axis_linear_map
std::map< std::string, int > axis_linear_map
Definition: teleop_twist_joy.cpp:53
teleop_twist_joy::TeleopTwistJoy::Impl::cmd_vel_pub
ros::Publisher cmd_vel_pub
Definition: teleop_twist_joy.cpp:48
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
teleop_twist_joy::TeleopTwistJoy::Impl::axis_angular_map
std::map< std::string, int > axis_angular_map
Definition: teleop_twist_joy.cpp:56
teleop_twist_joy::TeleopTwistJoy::Impl::joy_sub
ros::Subscriber joy_sub
Definition: teleop_twist_joy.cpp:47
teleop_twist_joy::TeleopTwistJoy::Impl::scale_angular_map
std::map< std::string, std::map< std::string, double > > scale_angular_map
Definition: teleop_twist_joy.cpp:57
teleop_twist_joy::TeleopTwistJoy::Impl::enable_button
int enable_button
Definition: teleop_twist_joy.cpp:50
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
teleop_twist_joy::TeleopTwistJoy::Impl
Definition: teleop_twist_joy.cpp:42
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
teleop_twist_joy.h
ROS_INFO_COND_NAMED
#define ROS_INFO_COND_NAMED(cond, name,...)
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
teleop_twist_joy::TeleopTwistJoy::TeleopTwistJoy
TeleopTwistJoy(ros::NodeHandle *nh, ros::NodeHandle *nh_param)
Definition: teleop_twist_joy.cpp:67
teleop_twist_joy::TeleopTwistJoy::Impl::scale_linear_map
std::map< std::string, std::map< std::string, double > > scale_linear_map
Definition: teleop_twist_joy.cpp:54
teleop_twist_joy::TeleopTwistJoy::pimpl_
Impl * pimpl_
Definition: teleop_twist_joy.h:42
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
teleop_twist_joy::TeleopTwistJoy::Impl::sendCmdVelMsg
void sendCmdVelMsg(const sensor_msgs::Joy::ConstPtr &joy_msg, const std::string &which_map)
Definition: teleop_twist_joy.cpp:140
teleop_twist_joy::TeleopTwistJoy::Impl::sent_disable_msg
bool sent_disable_msg
Definition: teleop_twist_joy.cpp:59
teleop_twist_joy
Definition: teleop_twist_joy.h:30
teleop_twist_joy::TeleopTwistJoy::Impl::joyCallback
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)
Definition: teleop_twist_joy.cpp:157
teleop_twist_joy::getVal
double getVal(const sensor_msgs::Joy::ConstPtr &joy_msg, const std::map< std::string, int > &axis_map, const std::map< std::string, double > &scale_map, const std::string &fieldname)
Definition: teleop_twist_joy.cpp:127
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
ros::NodeHandle
ros::Subscriber
teleop_twist_joy::TeleopTwistJoy::Impl::enable_turbo_button
int enable_turbo_button
Definition: teleop_twist_joy.cpp:51


teleop_twist_joy
Author(s): Mike Purvis
autogenerated on Wed Mar 2 2022 01:05:38