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
2 changes: 2 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,4 +53,6 @@ if (CATKIN_ENABLE_TESTING)
add_rostest(test/only_turbo_joy.test)
add_rostest(test/turbo_angular_enable_joy.test)
add_rostest(test/turbo_angular_enable_joy_with_rosparam_map.test)
add_rostest(test/enable_button_disabled_joy.test)
add_rostest(test/enable_button_disabled_turbo_enable_joy.test)
endif()
9 changes: 9 additions & 0 deletions config/ps3-noenable.config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
axis_linear: 1
scale_linear: 0.7
scale_linear_turbo: 1.5

axis_angular: 0
scale_angular: 0.4

enable_button: -1 # No need to press the enable_button
enable_turbo_button: 10 # L1 shoulder button
47 changes: 30 additions & 17 deletions src/teleop_twist_joy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,8 +46,8 @@ 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)

std::map<std::string, int> axis_linear_map;
std::map<std::string, double> scale_linear_map;
Expand Down Expand Up @@ -102,26 +102,39 @@ TeleopTwistJoy::TeleopTwistJoy(ros::NodeHandle* nh, ros::NodeHandle* nh_param)
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);

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,
"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 +145,7 @@ 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 && joy_msg->buttons[enable_turbo_button]) // Turbo button enabled AND pressed
{
if (axis_linear_map.find("x") != axis_linear_map.end())
{
Expand Down Expand Up @@ -162,7 +175,7 @@ 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 (joy_msg->buttons[enable_button] || enable_button < 0) // enable_button pressed OR enable_button disabled
{
if (axis_linear_map.find("x") != axis_linear_map.end())
{
Expand Down Expand Up @@ -194,8 +207,8 @@ void TeleopTwistJoy::Impl::joyCallback(const sensor_msgs::Joy::ConstPtr& joy_msg
}
else
{
// When enable button is released, immediately send a single no-motion command
// in order to stop the robot.
// When enable_button is released, immediately send a single no-motion command
// in order to stop the robot, unless enable_button is disabled (-1)
if (!sent_disable_msg)
{
cmd_vel_pub.publish(cmd_vel_msg);
Expand Down
22 changes: 22 additions & 0 deletions test/enable_button_disabled_joy.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<launch>
<node pkg="teleop_twist_joy" name="teleop_twist_joy" type="teleop_node">
<rosparam>
axis_linear: 1
axis_angular: 0
scale_linear: 2.0
scale_angular: 3.0
enable_button: -1
</rosparam>
</node>

<test test-name="no_enable_joy" pkg="teleop_twist_joy" type="test_joy_twist.py">
<rosparam>
publish_joy:
axes: [ 0.3, 0.4 ]
buttons: [ 0 ]
expect_cmd_vel:
linear: { x: 0.8, y: 0, z: 0 }
angular: { x: 0, y: 0, z: 0.9 }
</rosparam>
</test>
</launch>
24 changes: 24 additions & 0 deletions test/enable_button_disabled_turbo_enable_joy.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
<launch>
<node pkg="teleop_twist_joy" name="teleop_twist_joy" type="teleop_node">
<rosparam>
axis_linear: 1
axis_angular: 0
scale_linear: 1.0
scale_linear_turbo: 2.0
scale_angular: 3.0
enable_button: -1
enable_turbo_button: 1
</rosparam>
</node>

<test test-name="turbo_enable_joy" pkg="teleop_twist_joy" type="test_joy_twist.py">
<rosparam>
publish_joy:
axes: [ 0.3, 0.4 ]
buttons: [ 0, 1 ]
expect_cmd_vel:
linear: { x: 0.8, y: 0, z: 0 }
angular: { x: 0, y: 0, z: 0.9 }
</rosparam>
</test>
</launch>