Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add inactivity timer: if no activity after timeout, zero twist #25

Open
wants to merge 1 commit into
base: indigo-devel
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
46 changes: 46 additions & 0 deletions src/teleop_twist_joy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,12 @@ struct TeleopTwistJoy::Impl
std::map< std::string, std::map<std::string, double> > scale_angular_map;

bool sent_disable_msg;

double inactivity_timeout;
void restart_inactivity_timer(void);
void stop_inactivity_timer(void);
ros::Timer timer;
void inactivityTimerCallback(const ros::TimerEvent& e);
};

/**
Expand Down Expand Up @@ -122,6 +128,15 @@ TeleopTwistJoy::TeleopTwistJoy(ros::NodeHandle* nh, ros::NodeHandle* nh_param)
}

pimpl_->sent_disable_msg = false;

// if the inactivity_timeout is <= 0, it is disabled
nh_param->param<double>("inactivity_timeout", pimpl_->inactivity_timeout, -1.0);
// if the inactivity_timout is enabled, create a one-shot timer that is stopped
if (pimpl_->inactivity_timeout > 0.0)
{
pimpl_->timer = nh->createTimer(ros::Duration(pimpl_->inactivity_timeout),
&TeleopTwistJoy::Impl::inactivityTimerCallback, pimpl_, true, false);
}
}

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

cmd_vel_pub.publish(cmd_vel_msg);
sent_disable_msg = false;
restart_inactivity_timer();
}

void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg)
Expand All @@ -177,8 +193,38 @@ void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg
geometry_msgs::Twist cmd_vel_msg;
cmd_vel_pub.publish(cmd_vel_msg);
sent_disable_msg = true;
stop_inactivity_timer();
}
}
}

void TeleopTwistJoy::Impl::restart_inactivity_timer(void)
{
if (inactivity_timeout > 0.0)
{
timer.stop();
timer.setPeriod(ros::Duration(inactivity_timeout));
timer.start();
}
}

void TeleopTwistJoy::Impl::stop_inactivity_timer(void)
{
if (inactivity_timeout > 0.0)
{
timer.stop();
}
}

void TeleopTwistJoy::Impl::inactivityTimerCallback(const ros::TimerEvent& e)
{
if (!sent_disable_msg)
{
geometry_msgs::Twist cmd_vel_msg;
ROS_INFO_NAMED("TeleopTwistJoy", "Joystick timed out, stopping motion");
cmd_vel_pub.publish(cmd_vel_msg);
sent_disable_msg = true;
}
}

} // namespace teleop_twist_joy