Skip to content

Commit 449c1ff

Browse files
author
C. Andy Martin
committed
Add inactivity timer: if no activity after timeout, zero twist
Add an inactivity timer. Some wireless joysticks constantly transmit data (such as the Play Station Dualshock4). In such cases, it is possible to determine that the joystick is out of range and stop motion by the fact that activity slows down or ceases. This is useful for teleop in the case that the robot leaves range and a twist gets stuck commanding the robot to move without stopping. In this case, the inactivity timeout would detect no more messages after the threshold and send a zero twist (just as if the enable button were released). The default is for the inactivity timeout to be disabled. It can be enabled by setting the inactivity_timeout parameter.
1 parent 3e39c13 commit 449c1ff

File tree

1 file changed

+46
-0
lines changed

1 file changed

+46
-0
lines changed

src/teleop_twist_joy.cpp

Lines changed: 46 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,12 @@ struct TeleopTwistJoy::Impl
5858
std::map<std::string, double> scale_angular_turbo_map;
5959

6060
bool sent_disable_msg;
61+
62+
double inactivity_timeout;
63+
void restart_inactivity_timer(void);
64+
void stop_inactivity_timer(void);
65+
ros::Timer timer;
66+
void inactivityTimerCallback(const ros::TimerEvent& e);
6167
};
6268

6369
/**
@@ -125,6 +131,14 @@ TeleopTwistJoy::TeleopTwistJoy(ros::NodeHandle* nh, ros::NodeHandle* nh_param)
125131
}
126132

127133
pimpl_->sent_disable_msg = false;
134+
135+
// if the inactivity_timeout is <= 0, it is disabled
136+
nh_param->param<double>("inactivity_timeout", pimpl_->inactivity_timeout, -1.0);
137+
// if the inactivity_timout is enabled, create a one-shot timer that is stopped
138+
if (pimpl_->inactivity_timeout > 0.0)
139+
{
140+
pimpl_->timer = nh->createTimer(ros::Duration(pimpl_->inactivity_timeout), &TeleopTwistJoy::Impl::inactivityTimerCallback, pimpl_, true, false);
141+
}
128142
}
129143

130144
void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg)
@@ -161,6 +175,7 @@ void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg
161175

162176
cmd_vel_pub.publish(cmd_vel_msg);
163177
sent_disable_msg = false;
178+
restart_inactivity_timer();
164179
}
165180
else if (joy_msg->buttons[enable_button])
166181
{
@@ -191,6 +206,7 @@ void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg
191206

192207
cmd_vel_pub.publish(cmd_vel_msg);
193208
sent_disable_msg = false;
209+
restart_inactivity_timer();
194210
}
195211
else
196212
{
@@ -200,8 +216,38 @@ void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg
200216
{
201217
cmd_vel_pub.publish(cmd_vel_msg);
202218
sent_disable_msg = true;
219+
stop_inactivity_timer();
203220
}
204221
}
205222
}
206223

224+
void TeleopTwistJoy::Impl::restart_inactivity_timer(void)
225+
{
226+
if (inactivity_timeout > 0.0)
227+
{
228+
timer.stop();
229+
timer.setPeriod(ros::Duration(inactivity_timeout));
230+
timer.start();
231+
}
232+
}
233+
234+
void TeleopTwistJoy::Impl::stop_inactivity_timer(void)
235+
{
236+
if (inactivity_timeout > 0.0)
237+
{
238+
timer.stop();
239+
}
240+
}
241+
242+
void TeleopTwistJoy::Impl::inactivityTimerCallback(const ros::TimerEvent& e)
243+
{
244+
if (!sent_disable_msg)
245+
{
246+
geometry_msgs::Twist cmd_vel_msg;
247+
ROS_INFO_NAMED("TeleopTwistJoy", "Joystick timed out, stopping motion");
248+
cmd_vel_pub.publish(cmd_vel_msg);
249+
sent_disable_msg = true;
250+
}
251+
}
252+
207253
} // namespace teleop_twist_joy

0 commit comments

Comments
 (0)