35 #include <geometry_msgs/Twist.h> 36 #include <sensor_msgs/Joy.h> 37 #include <std_msgs/Bool.h> 67 float getAxisValue(
const sensor_msgs::Joy::Ptr& msg,
const int axis,
const std::string& axis_name)
const 73 if (static_cast<size_t>(axis) >= msg->axes.size())
75 ROS_ERROR(
"Out of range: number of axis (%lu) must be greater than %s (%d).",
76 msg->axes.size(), axis_name.c_str(), axis);
79 return msg->axes[axis];
82 float getJoyValue(
const sensor_msgs::Joy::Ptr& msg,
const int axis,
const int axis2,
83 const std::string& axis_name)
const 86 const float value2 =
getAxisValue(msg, axis2, axis_name +
"2");
87 return (std::abs(value2) > std::abs(value)) ? value2 : value;
90 void cbJoy(
const sensor_msgs::Joy::Ptr msg)
92 if (static_cast<size_t>(interrupt_button_) >= msg->buttons.size())
94 ROS_ERROR(
"Out of range: number of buttons (%lu) must be greater than interrupt_button (%d).",
99 if (!msg->buttons[interrupt_button_])
103 pub_twist_.
publish(last_input_twist_);
111 float lin_x =
getJoyValue(msg, linear_axis_, linear_axis2_,
"linear_axis");
112 float lin_y =
getJoyValue(msg, linear_y_axis_, linear_y_axis2_,
"linear_y_axis");
113 float ang =
getJoyValue(msg, angular_axis_, angular_axis2_,
"angular_axis");
115 if (high_speed_button_ >= 0)
117 if (static_cast<size_t>(high_speed_button_) < msg->buttons.size())
119 if (msg->buttons[high_speed_button_])
127 ROS_ERROR(
"Out of range: number of buttons (%lu) must be greater than high_speed_button (%d).",
131 geometry_msgs::Twist cmd_vel;
134 cmd_vel.linear.z = 0.0;
136 cmd_vel.angular.x = cmd_vel.angular.y = 0.0;
139 void cbTwist(
const geometry_msgs::Twist::Ptr msg)
141 last_input_twist_ = *msg;
142 std_msgs::Bool status;
146 pub_twist_.
publish(last_input_twist_);
164 nh_,
"cmd_vel_input",
166 pub_twist_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
169 pub_int_ = pnh_.advertise<std_msgs::Bool>(
"interrupt_status", 2);
171 pnh_.param(
"linear_vel", linear_vel_, 0.5);
172 pnh_.param(
"angular_vel", angular_vel_, 0.8);
173 pnh_.param(
"linear_axis", linear_axis_, 1);
174 pnh_.param(
"angular_axis", angular_axis_, 0);
175 pnh_.param(
"linear_axis2", linear_axis2_, -1);
176 pnh_.param(
"angular_axis2", angular_axis2_, -1);
177 pnh_.param(
"interrupt_button", interrupt_button_, 6);
178 pnh_.param(
"high_speed_button", high_speed_button_, -1);
179 pnh_.param(
"linear_high_speed_ratio", linear_high_speed_ratio_, 1.3);
180 pnh_.param(
"angular_high_speed_ratio", angular_high_speed_ratio_, 1.1);
181 pnh_.param(
"timeout", timeout_, 0.5);
182 pnh_.param(
"linear_y_vel", linear_y_vel_, 0.0);
183 pnh_.param(
"linear_y_axis", linear_y_axis_, -1);
184 pnh_.param(
"linear_y_axis2", linear_y_axis2_, -1);
188 if (interrupt_button_ < 0)
190 ROS_ERROR(
"interrupt_button must be grater than -1.");
194 if (linear_axis_ < 0)
196 ROS_ERROR(
"linear_axis must be grater than -1.");
200 if (angular_axis_ < 0)
202 ROS_ERROR(
"angular_axis must be grater than -1.");
209 int main(
int argc,
char* argv[])
211 ros::init(argc, argv,
"joystick_interrupt");
double linear_high_speed_ratio_
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)
geometry_msgs::Twist last_input_twist_
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_
void publish(const boost::shared_ptr< M > &message) const
double angular_high_speed_ratio_
ROSCPP_DECL void shutdown()
float getAxisValue(const sensor_msgs::Joy::Ptr &msg, const int axis, const std::string &axis_name) const
void cbTwist(const geometry_msgs::Twist::Ptr msg)
float getJoyValue(const sensor_msgs::Joy::Ptr &msg, const int axis, const int axis2, const std::string &axis_name) const