Go to the documentation of this file.
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)
94 ROS_ERROR(
"Out of range: number of buttons (%lu) must be greater than interrupt_button (%d).",
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)
142 std_msgs::Bool status;
164 nh_,
"cmd_vel_input",
166 pub_twist_ = neonavigation_common::compat::advertise<geometry_msgs::Twist>(
190 ROS_ERROR(
"interrupt_button must be grater than -1.");
196 ROS_ERROR(
"linear_axis must be grater than -1.");
202 ROS_ERROR(
"angular_axis must be grater than -1.");
209 int main(
int argc,
char* argv[])
211 ros::init(argc, argv,
"joystick_interrupt");
ros::Subscriber sub_twist_
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
float getJoyValue(const sensor_msgs::Joy::Ptr &msg, const int axis, const int axis2, const std::string &axis_name) const
ROSCPP_DECL void shutdown()
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
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, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr(), const ros::TransportHints &transport_hints=ros::TransportHints())
int main(int argc, char *argv[])
geometry_msgs::Twist last_input_twist_
double angular_high_speed_ratio_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Publisher pub_twist_
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)
T param(const std::string ¶m_name, const T &default_val) const
double linear_high_speed_ratio_
void cbJoy(const sensor_msgs::Joy::Ptr msg)