39 #include "geometry_msgs/TwistStamped.h" 40 #include "control_msgs/JointJog.h" 42 #include "sensor_msgs/Joy.h" 69 geometry_msgs::TwistStamped twist;
71 twist.twist.linear.x = msg->axes[0];
72 twist.twist.linear.y = msg->axes[1];
73 twist.twist.linear.z = msg->axes[2];
75 twist.twist.angular.x = msg->axes[3];
76 twist.twist.angular.y = msg->axes[4];
77 twist.twist.angular.z = msg->axes[5];
80 control_msgs::JointJog joint_deltas;
82 joint_deltas.joint_names.push_back(
"shoulder_pan_joint");
86 joint_deltas.velocities.push_back(msg->buttons[0] - msg->buttons[1]);
100 int main(
int argc,
char** argv)
102 ros::init(argc, argv,
"spacenav_to_twist");
ros::AsyncSpinner spinner_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static const int NUM_SPINNERS
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void joyCallback(const sensor_msgs::Joy::ConstPtr &msg)
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
static const int QUEUE_LENGTH
ros::Publisher joint_delta_pub_
ros::Publisher twist_pub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void waitForShutdown()