00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <ros/ros.h>
00031 #include <geometry_msgs/Twist.h>
00032 #include <sensor_msgs/Joy.h>
00033 #include <std_msgs/Bool.h>
00034
00035 #include <neonavigation_common/compatibility.h>
00036
00037 class JoystickInterrupt
00038 {
00039 private:
00040 ros::NodeHandle nh_;
00041 ros::NodeHandle pnh_;
00042 ros::Subscriber sub_twist_;
00043 ros::Subscriber sub_joy_;
00044 ros::Publisher pub_twist_;
00045 ros::Publisher pub_int_;
00046 double linear_vel_;
00047 double angular_vel_;
00048 double timeout_;
00049 double linear_high_speed_ratio_;
00050 double angular_high_speed_ratio_;
00051 int linear_axis_;
00052 int angular_axis_;
00053 int linear_axis2_;
00054 int angular_axis2_;
00055 int interrupt_button_;
00056 int high_speed_button_;
00057 ros::Time last_joy_msg_;
00058
00059 void cbJoy(const sensor_msgs::Joy::Ptr msg)
00060 {
00061 if (static_cast<size_t>(interrupt_button_) >= msg->buttons.size())
00062 {
00063 ROS_ERROR("Out of range: number of buttons (%lu) must be greater than interrupt_button (%d).",
00064 msg->buttons.size(), interrupt_button_);
00065 last_joy_msg_ = ros::Time(0);
00066 return;
00067 }
00068 if (!msg->buttons[interrupt_button_])
00069 {
00070 last_joy_msg_ = ros::Time(0);
00071 return;
00072 }
00073
00074 last_joy_msg_ = ros::Time::now();
00075
00076 float lin(0.0f);
00077 float ang(0.0f);
00078 if (static_cast<size_t>(linear_axis_) < msg->axes.size())
00079 lin = msg->axes[linear_axis_];
00080 else
00081 ROS_ERROR("Out of range: number of axis (%lu) must be greater than linear_axis (%d).",
00082 msg->axes.size(), linear_axis_);
00083 if (static_cast<size_t>(angular_axis_) < msg->axes.size())
00084 ang = msg->axes[angular_axis_];
00085 else
00086 ROS_ERROR("Out of range: number of axis (%lu) must be greater than angular_axis (%d).",
00087 msg->axes.size(), angular_axis_);
00088
00089 if (linear_axis2_ >= 0)
00090 {
00091 if (static_cast<size_t>(linear_axis2_) < msg->axes.size())
00092 {
00093 if (fabs(msg->axes[linear_axis2_]) > fabs(lin))
00094 lin = msg->axes[linear_axis2_];
00095 }
00096 else
00097 ROS_ERROR("Out of range: number of axis (%lu) must be greater than linear_axis2 (%d).",
00098 msg->axes.size(), linear_axis2_);
00099 }
00100 if (angular_axis2_ >= 0)
00101 {
00102 if (static_cast<size_t>(angular_axis2_) < msg->axes.size())
00103 {
00104 if (fabs(msg->axes[angular_axis2_]) > fabs(ang))
00105 ang = msg->axes[angular_axis2_];
00106 }
00107 else
00108 ROS_ERROR("Out of range: number of axis (%lu) must be greater than angular_axis2 (%d).",
00109 msg->axes.size(), angular_axis2_);
00110 }
00111
00112 if (high_speed_button_ >= 0)
00113 {
00114 if (static_cast<size_t>(high_speed_button_) < msg->buttons.size())
00115 {
00116 if (msg->buttons[high_speed_button_])
00117 {
00118 lin *= linear_high_speed_ratio_;
00119 ang *= angular_high_speed_ratio_;
00120 }
00121 }
00122 else
00123 ROS_ERROR("Out of range: number of buttons (%lu) must be greater than high_speed_button (%d).",
00124 msg->buttons.size(), high_speed_button_);
00125 }
00126
00127 geometry_msgs::Twist cmd_vel;
00128 cmd_vel.linear.x = lin * linear_vel_;
00129 cmd_vel.linear.y = cmd_vel.linear.z = 0.0;
00130 cmd_vel.angular.z = ang * angular_vel_;
00131 cmd_vel.angular.x = cmd_vel.angular.y = 0.0;
00132 pub_twist_.publish(cmd_vel);
00133 };
00134 void cbTwist(const geometry_msgs::Twist::Ptr msg)
00135 {
00136 std_msgs::Bool status;
00137 if (ros::Time::now() - last_joy_msg_ > ros::Duration(timeout_))
00138 {
00139 pub_twist_.publish(*msg);
00140 status.data = true;
00141 }
00142 else
00143 {
00144 status.data = false;
00145 }
00146 pub_int_.publish(status);
00147 };
00148
00149 public:
00150 JoystickInterrupt()
00151 : nh_("")
00152 , pnh_("~")
00153 {
00154 neonavigation_common::compat::checkCompatMode();
00155 sub_joy_ = nh_.subscribe("joy", 1, &JoystickInterrupt::cbJoy, this);
00156 sub_twist_ = neonavigation_common::compat::subscribe(
00157 nh_, "cmd_vel_input",
00158 pnh_, "cmd_vel_input", 1, &JoystickInterrupt::cbTwist, this);
00159 pub_twist_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
00160 nh_, "cmd_vel",
00161 pnh_, "cmd_vel", 2);
00162 pub_int_ = pnh_.advertise<std_msgs::Bool>("interrupt_status", 2);
00163
00164 pnh_.param("linear_vel", linear_vel_, 0.5);
00165 pnh_.param("angular_vel", angular_vel_, 0.8);
00166 pnh_.param("linear_axis", linear_axis_, 1);
00167 pnh_.param("angular_axis", angular_axis_, 0);
00168 pnh_.param("linear_axis2", linear_axis2_, -1);
00169 pnh_.param("angular_axis2", angular_axis2_, -1);
00170 pnh_.param("interrupt_button", interrupt_button_, 6);
00171 pnh_.param("high_speed_button", high_speed_button_, -1);
00172 pnh_.param("linear_high_speed_ratio", linear_high_speed_ratio_, 1.3);
00173 pnh_.param("angular_high_speed_ratio", angular_high_speed_ratio_, 1.1);
00174 pnh_.param("timeout", timeout_, 0.5);
00175 last_joy_msg_ = ros::Time(0);
00176
00177 if (interrupt_button_ < 0)
00178 {
00179 ROS_ERROR("interrupt_button must be grater than -1.");
00180 ros::shutdown();
00181 return;
00182 }
00183 if (linear_axis_ < 0)
00184 {
00185 ROS_ERROR("linear_axis must be grater than -1.");
00186 ros::shutdown();
00187 return;
00188 }
00189 if (angular_axis_ < 0)
00190 {
00191 ROS_ERROR("angular_axis must be grater than -1.");
00192 ros::shutdown();
00193 return;
00194 }
00195 }
00196 };
00197
00198 int main(int argc, char* argv[])
00199 {
00200 ros::init(argc, argv, "joystick_interrupt");
00201
00202 JoystickInterrupt jy;
00203 ros::spin();
00204
00205 return 0;
00206 }