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

ENABLE_BUTTON is now optional. Also added a braking button. #22

Open
wants to merge 10 commits into
base: indigo-devel
Choose a base branch
from
54 changes: 38 additions & 16 deletions src/teleop_twist_joy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,9 @@ struct TeleopTwistJoy::Impl
ros::Subscriber joy_sub;
ros::Publisher cmd_vel_pub;

int enable_button;
int enable_turbo_button;
int enable_button; // Enable normal motion. Defaults to joystick button 0
int enable_turbo_button; // Enable sprint by using alternative gain. By default disabled (-1)
int break_button; // Send break no-motion command. By default disabled (-1)

std::map<std::string, int> axis_linear_map;
std::map<std::string, double> scale_linear_map;
Expand All @@ -74,6 +75,7 @@ TeleopTwistJoy::TeleopTwistJoy(ros::NodeHandle* nh, ros::NodeHandle* nh_param)

nh_param->param<int>("enable_button", pimpl_->enable_button, 0);
nh_param->param<int>("enable_turbo_button", pimpl_->enable_turbo_button, -1);
nh_param->param<int>("break_button", pimpl_->break_button, -1);

if (nh_param->getParam("axis_linear", pimpl_->axis_linear_map))
{
Expand Down Expand Up @@ -101,27 +103,44 @@ TeleopTwistJoy::TeleopTwistJoy(ros::NodeHandle* nh, ros::NodeHandle* nh_param)
nh_param->param<double>("scale_angular_turbo",
pimpl_->scale_angular_turbo_map["yaw"], pimpl_->scale_angular_map["yaw"]);
}

ROS_INFO_NAMED("TeleopTwistJoy", "Teleop enable button %i.", pimpl_->enable_button);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
"Turbo on button %i.", pimpl_->enable_turbo_button);

ROS_INFO_COND_NAMED(pimpl_->enable_button >= 0,
"TeleopTwistJoy",
"Teleop enable button %i.",
pimpl_->enable_button);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0,
"TeleopTwistJoy",
"Turbo on button %i.",
pimpl_->enable_turbo_button);
ROS_INFO_COND_NAMED(pimpl_->break_button >= 0,
"TeleopTwistJoy",
"Breaking on button %i.",
pimpl_->break_button);

for (std::map<std::string, int>::iterator it = pimpl_->axis_linear_map.begin();
it != pimpl_->axis_linear_map.end(); ++it)
{
ROS_INFO_NAMED("TeleopTwistJoy", "Linear axis %s on %i at scale %f.",
it->first.c_str(), it->second, pimpl_->scale_linear_map[it->first]);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
"Turbo for linear axis %s is scale %f.", it->first.c_str(), pimpl_->scale_linear_turbo_map[it->first]);
ROS_INFO_COND_NAMED(pimpl_->enable_button >= 0,
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Extra space here and below.

"TeleopTwistJoy",
"Linear axis %s on %i at scale %f.",
it->first.c_str(), it->second, pimpl_->scale_linear_map[it->first]);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0,
"TeleopTwistJoy",
"Turbo for linear axis %s is scale %f.",
it->first.c_str(), pimpl_->scale_linear_turbo_map[it->first]);
}

for (std::map<std::string, int>::iterator it = pimpl_->axis_angular_map.begin();
it != pimpl_->axis_angular_map.end(); ++it)
{
ROS_INFO_NAMED("TeleopTwistJoy", "Angular axis %s on %i at scale %f.",
it->first.c_str(), it->second, pimpl_->scale_angular_map[it->first]);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0, "TeleopTwistJoy",
"Turbo for angular axis %s is scale %f.", it->first.c_str(), pimpl_->scale_angular_turbo_map[it->first]);
ROS_INFO_COND_NAMED(pimpl_->enable_button >= 0,
"TeleopTwistJoy",
"Angular axis %s on %i at scale %f.",
it->first.c_str(), it->second, pimpl_->scale_angular_map[it->first]);
ROS_INFO_COND_NAMED(pimpl_->enable_turbo_button >= 0,
"TeleopTwistJoy",
"Turbo for angular axis %s is scale %f.",
it->first.c_str(), pimpl_->scale_angular_turbo_map[it->first]);
}

pimpl_->sent_disable_msg = false;
Expand All @@ -132,7 +151,9 @@ void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg
// Initializes with zeros by default.
geometry_msgs::Twist cmd_vel_msg;

if (enable_turbo_button >= 0 && joy_msg->buttons[enable_turbo_button])
if (enable_turbo_button >= 0 && // turbo_button enabled AND
joy_msg->buttons[enable_turbo_button] && // turbo_button pressed AND
!joy_msg->buttons[break_button] ) // break_button not pressed
{
if (axis_linear_map.find("x") != axis_linear_map.end())
{
Expand Down Expand Up @@ -162,7 +183,8 @@ void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg
cmd_vel_pub.publish(cmd_vel_msg);
sent_disable_msg = false;
}
else if (joy_msg->buttons[enable_button])
else if ( (enable_button < 0 || joy_msg->buttons[enable_button]) && // (enable_button not enabled OR enable_button pressed ) AND
!joy_msg->buttons[break_button] ) // breaking_button not pressed
{
if (axis_linear_map.find("x") != axis_linear_map.end())
{
Expand Down