Skip to content

Commit a858462

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 e5406f9 commit a858462

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
@@ -57,6 +57,12 @@ struct TeleopTwistJoy::Impl
5757
std::map< std::string, std::map<std::string, double> > scale_angular_map;
5858

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

6268
/**
@@ -122,6 +128,15 @@ TeleopTwistJoy::TeleopTwistJoy(ros::NodeHandle* nh, ros::NodeHandle* nh_param)
122128
}
123129

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

127142
double getVal(const sensor_msgs::Joy::ConstPtr& joy_msg, const std::map<std::string, int>& axis_map,
@@ -152,6 +167,7 @@ void TeleopTwistJoy::Impl::sendCmdVelMsg(const sensor_msgs::Joy::ConstPtr& joy_m
152167

153168
cmd_vel_pub.publish(cmd_vel_msg);
154169
sent_disable_msg = false;
170+
restart_inactivity_timer();
155171
}
156172

157173
void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg)
@@ -177,8 +193,38 @@ void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg
177193
geometry_msgs::Twist cmd_vel_msg;
178194
cmd_vel_pub.publish(cmd_vel_msg);
179195
sent_disable_msg = true;
196+
stop_inactivity_timer();
180197
}
181198
}
182199
}
183200

201+
void TeleopTwistJoy::Impl::restart_inactivity_timer(void)
202+
{
203+
if (inactivity_timeout > 0.0)
204+
{
205+
timer.stop();
206+
timer.setPeriod(ros::Duration(inactivity_timeout));
207+
timer.start();
208+
}
209+
}
210+
211+
void TeleopTwistJoy::Impl::stop_inactivity_timer(void)
212+
{
213+
if (inactivity_timeout > 0.0)
214+
{
215+
timer.stop();
216+
}
217+
}
218+
219+
void TeleopTwistJoy::Impl::inactivityTimerCallback(const ros::TimerEvent& e)
220+
{
221+
if (!sent_disable_msg)
222+
{
223+
geometry_msgs::Twist cmd_vel_msg;
224+
ROS_INFO_NAMED("TeleopTwistJoy", "Joystick timed out, stopping motion");
225+
cmd_vel_pub.publish(cmd_vel_msg);
226+
sent_disable_msg = true;
227+
}
228+
}
229+
184230
} // namespace teleop_twist_joy

0 commit comments

Comments
 (0)