31 #include <geometry_msgs/Twist.h> 32 #include <sensor_msgs/Joy.h> 33 #include <std_msgs/Bool.h> 59 void cbJoy(
const sensor_msgs::Joy::Ptr msg)
61 if (static_cast<size_t>(interrupt_button_) >= msg->buttons.size())
63 ROS_ERROR(
"Out of range: number of buttons (%lu) must be greater than interrupt_button (%d).",
68 if (!msg->buttons[interrupt_button_])
78 if (static_cast<size_t>(linear_axis_) < msg->axes.size())
79 lin = msg->axes[linear_axis_];
81 ROS_ERROR(
"Out of range: number of axis (%lu) must be greater than linear_axis (%d).",
83 if (static_cast<size_t>(angular_axis_) < msg->axes.size())
84 ang = msg->axes[angular_axis_];
86 ROS_ERROR(
"Out of range: number of axis (%lu) must be greater than angular_axis (%d).",
89 if (linear_axis2_ >= 0)
91 if (static_cast<size_t>(linear_axis2_) < msg->axes.size())
93 if (fabs(msg->axes[linear_axis2_]) > fabs(lin))
94 lin = msg->axes[linear_axis2_];
97 ROS_ERROR(
"Out of range: number of axis (%lu) must be greater than linear_axis2 (%d).",
100 if (angular_axis2_ >= 0)
102 if (static_cast<size_t>(angular_axis2_) < msg->axes.size())
104 if (fabs(msg->axes[angular_axis2_]) > fabs(ang))
105 ang = msg->axes[angular_axis2_];
108 ROS_ERROR(
"Out of range: number of axis (%lu) must be greater than angular_axis2 (%d).",
112 if (high_speed_button_ >= 0)
114 if (static_cast<size_t>(high_speed_button_) < msg->buttons.size())
116 if (msg->buttons[high_speed_button_])
123 ROS_ERROR(
"Out of range: number of buttons (%lu) must be greater than high_speed_button (%d).",
127 geometry_msgs::Twist cmd_vel;
129 cmd_vel.linear.y = cmd_vel.linear.z = 0.0;
131 cmd_vel.angular.x = cmd_vel.angular.y = 0.0;
134 void cbTwist(
const geometry_msgs::Twist::Ptr msg)
136 std_msgs::Bool status;
157 nh_,
"cmd_vel_input",
159 pub_twist_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
162 pub_int_ = pnh_.advertise<std_msgs::Bool>(
"interrupt_status", 2);
164 pnh_.param(
"linear_vel", linear_vel_, 0.5);
165 pnh_.param(
"angular_vel", angular_vel_, 0.8);
166 pnh_.param(
"linear_axis", linear_axis_, 1);
167 pnh_.param(
"angular_axis", angular_axis_, 0);
168 pnh_.param(
"linear_axis2", linear_axis2_, -1);
169 pnh_.param(
"angular_axis2", angular_axis2_, -1);
170 pnh_.param(
"interrupt_button", interrupt_button_, 6);
171 pnh_.param(
"high_speed_button", high_speed_button_, -1);
172 pnh_.param(
"linear_high_speed_ratio", linear_high_speed_ratio_, 1.3);
173 pnh_.param(
"angular_high_speed_ratio", angular_high_speed_ratio_, 1.1);
174 pnh_.param(
"timeout", timeout_, 0.5);
177 if (interrupt_button_ < 0)
179 ROS_ERROR(
"interrupt_button must be grater than -1.");
183 if (linear_axis_ < 0)
185 ROS_ERROR(
"linear_axis must be grater than -1.");
189 if (angular_axis_ < 0)
191 ROS_ERROR(
"angular_axis must be grater than -1.");
198 int main(
int argc,
char* argv[])
200 ros::init(argc, argv,
"joystick_interrupt");
double linear_high_speed_ratio_
void publish(const boost::shared_ptr< M > &message) const
void cbJoy(const sensor_msgs::Joy::Ptr msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
ros::Subscriber sub_twist_
int main(int argc, char *argv[])
ros::Publisher pub_twist_
double angular_high_speed_ratio_
ROSCPP_DECL void shutdown()
void cbTwist(const geometry_msgs::Twist::Ptr msg)