Go to the documentation of this file.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
00031
00032
00033
00034
00035 #include "head_pointer.h"
00036
00037 HeadPointer::HeadPointer( ros::NodeHandle pnh, std::string action_topic ) :
00038 point_head_action_client_(action_topic, true)
00039 {
00040 joy_sub_ = nh_.subscribe<sensor_msgs::Joy>( "joy", 1, boost::bind(&HeadPointer::joyCb, this, _1) );
00041
00042 pnh.param<std::string>( "tracked_frame", point_head_goal_.target.header.frame_id, "oculus" );
00043 pnh.param<std::string>( "pointing_frame", point_head_goal_.pointing_frame, "head_mount_kinect_rgb_link" );
00044 pnh.param<int>( "deadman_button", deadman_button_, 0 );
00045
00046 point_head_goal_.pointing_axis.x = 1;
00047 point_head_goal_.pointing_axis.y = 0;
00048 point_head_goal_.pointing_axis.z = 0;
00049
00050 point_head_goal_.target.point.x = 2;
00051 point_head_goal_.target.point.y = 0;
00052 point_head_goal_.target.point.z = 0;
00053
00054 point_head_goal_.max_velocity = 1.0;
00055
00056 pnh.param<double>( "update_freq", update_freq_, 0.1 );
00057 }
00058
00059 HeadPointer::~HeadPointer()
00060 {
00061 }
00062
00063 void HeadPointer::joyCb( sensor_msgs::JoyConstPtr joy_msg )
00064 {
00065 if ( ros::Time::now() - last_update_time_ < ros::Duration(update_freq_) )
00066 {
00067 return;
00068 }
00069
00070 if ( joy_msg->buttons.size() <= deadman_button_ )
00071 {
00072 ROS_ERROR_ONCE("Button index for deadman switch is out of bounds!");
00073 return;
00074 }
00075
00076 if ( joy_msg->buttons.at(deadman_button_) )
00077 {
00078 last_update_time_ = ros::Time::now();
00079
00080 point_head_action_client_.sendGoal( point_head_goal_ );
00081 }
00082 }