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 <ros/ros.h>
00036 #include <sensor_msgs/Joy.h>
00037 #include <geometry_msgs/Twist.h>
00038 #include <robotnik_msgs/ptz.h>
00039
00040
00041 #include <unistd.h>
00042 #include <robotnik_msgs/set_mode.h>
00043 #include <robotnik_msgs/set_digital_output.h>
00044 #include <robotnik_msgs/ptz.h>
00045 #include <robotnik_msgs/home.h>
00046 #include <diagnostic_updater/diagnostic_updater.h>
00047 #include <diagnostic_updater/publisher.h>
00048
00049 #define DEFAULT_NUM_OF_BUTTONS 16
00050 #define DEFAULT_AXIS_LINEAR_X 1
00051 #define DEFAULT_AXIS_LINEAR_Y 0
00052 #define DEFAULT_AXIS_ANGULAR 2
00053 #define DEFAULT_AXIS_LINEAR_Z 3
00054 #define DEFAULT_SCALE_LINEAR 1.0
00055 #define DEFAULT_SCALE_ANGULAR 2.0
00056 #define DEFAULT_SCALE_LINEAR_Z 1.0
00057
00058
00059 #define AXIS_PTZ_TILT_UP 0
00060 #define AXIS_PTZ_TILT_DOWN 1
00061 #define AXIS_PTZ_PAN_LEFT 2
00062 #define AXIS_PTZ_PAN_RIGHT 3
00063
00064
00066
00067
00068
00069
00070
00071
00072 class SummitXLPad
00073 {
00074 public:
00075 SummitXLPad();
00076 void Update();
00077
00078 private:
00079 void padCallback(const sensor_msgs::Joy::ConstPtr& joy);
00080 ros::NodeHandle nh_;
00081
00082 int linear_x_, linear_y_, linear_z_, angular_;
00083 double l_scale_, a_scale_, l_scale_z_;
00085 ros::Publisher vel_pub_, ptz_pub_;
00087 ros::Subscriber pad_sub_;
00089 std::string cmd_topic_vel_;
00091 std::string cmd_service_io_;
00093 std::string cmd_topic_ptz_;
00094 double current_vel;
00096 std::string pad_type_;
00098 int dead_man_button_;
00100 int speed_up_button_, speed_down_button_;
00101 int button_output_1_, button_output_2_;
00102 int output_1_, output_2_;
00103 bool bOutput1, bOutput2;
00105 int button_kinematic_mode_;
00107 int kinematic_mode_;
00109 ros::ServiceClient setKinematicMode;
00111 std::string cmd_set_mode_;
00113 int button_home_;
00115 ros::ServiceClient doHome;
00117 std::string cmd_home_;
00119 int ptz_tilt_up_, ptz_tilt_down_, ptz_pan_right_, ptz_pan_left_;
00120 int ptz_zoom_wide_, ptz_zoom_tele_;
00122 ros::ServiceClient set_digital_outputs_client_;
00124 int num_of_buttons_;
00126 bool bRegisteredButtonEvent[DEFAULT_NUM_OF_BUTTONS];
00128 bool bRegisteredDirectionalArrows[4];
00129
00130
00132 diagnostic_updater::HeaderlessTopicDiagnostic *pub_command_freq;
00134 diagnostic_updater::HeaderlessTopicDiagnostic *sus_joy_freq;
00136 diagnostic_updater::Updater updater_pad;
00138 double min_freq_command, min_freq_joy;
00140 double max_freq_command, max_freq_joy;
00142 bool bEnable;
00144 bool last_command_;
00146
00148 int pan_increment_, tilt_increment_;
00150 int zoom_increment_;
00152 std::string joystick_dead_zone_;
00153 };
00154
00155
00156 SummitXLPad::SummitXLPad():
00157 linear_x_(1),
00158 linear_y_(0),
00159 angular_(2),
00160 linear_z_(3)
00161 {
00162 current_vel = 0.1;
00163
00164
00165 nh_.param<std::string>("pad_type",pad_type_,"ps3");
00166
00167 nh_.param("num_of_buttons", num_of_buttons_, DEFAULT_NUM_OF_BUTTONS);
00168
00169 nh_.param("axis_linear_x", linear_x_, DEFAULT_AXIS_LINEAR_X);
00170 nh_.param("axis_linear_y", linear_y_, DEFAULT_AXIS_LINEAR_Y);
00171 nh_.param("axis_linear_z", linear_z_, DEFAULT_AXIS_LINEAR_Z);
00172 nh_.param("axis_angular", angular_, DEFAULT_AXIS_ANGULAR);
00173 nh_.param("scale_angular", a_scale_, DEFAULT_SCALE_ANGULAR);
00174 nh_.param("scale_linear", l_scale_, DEFAULT_SCALE_LINEAR);
00175 nh_.param("scale_linear_z", l_scale_z_, DEFAULT_SCALE_LINEAR_Z);
00176 nh_.param("cmd_topic_vel", cmd_topic_vel_, cmd_topic_vel_);
00177 nh_.param("button_dead_man", dead_man_button_, dead_man_button_);
00178 nh_.param("button_speed_up", speed_up_button_, speed_up_button_);
00179 nh_.param("button_speed_down", speed_down_button_, speed_down_button_);
00180 nh_.param<std::string>("joystick_dead_zone", joystick_dead_zone_, "true");
00181
00182
00183 nh_.param("cmd_service_io", cmd_service_io_, cmd_service_io_);
00184 nh_.param("button_output_1", button_output_1_, button_output_1_);
00185 nh_.param("button_output_2", button_output_2_, button_output_2_);
00186 nh_.param("output_1", output_1_, output_1_);
00187 nh_.param("output_2", output_2_, output_2_);
00188
00189 nh_.param("cmd_topic_ptz", cmd_topic_ptz_, cmd_topic_ptz_);
00190 nh_.param("button_ptz_tilt_up", ptz_tilt_up_, ptz_tilt_up_);
00191 nh_.param("button_ptz_tilt_down", ptz_tilt_down_, ptz_tilt_down_);
00192 nh_.param("button_ptz_pan_right", ptz_pan_right_, ptz_pan_right_);
00193 nh_.param("button_ptz_pan_left", ptz_pan_left_, ptz_pan_left_);
00194 nh_.param("button_ptz_zoom_wide", ptz_zoom_wide_, ptz_zoom_wide_);
00195 nh_.param("button_ptz_zoom_tele", ptz_zoom_tele_, ptz_zoom_tele_);
00196 nh_.param("button_home", button_home_, button_home_);
00197 nh_.param("pan_increment", pan_increment_, 1);
00198 nh_.param("tilt_increment",tilt_increment_, 1);
00199 nh_.param("zoom_increment", zoom_increment_, 1);
00200
00201
00202 nh_.param("button_kinematic_mode", button_kinematic_mode_, button_kinematic_mode_);
00203 nh_.param("cmd_service_set_mode", cmd_set_mode_, cmd_set_mode_);
00204 nh_.param("cmd_service_home", cmd_home_, cmd_home_);
00205 kinematic_mode_ = 1;
00206
00207 ROS_INFO("SummitXLPad num_of_buttons_ = %d", num_of_buttons_);
00208 for(int i = 0; i < num_of_buttons_; i++){
00209 bRegisteredButtonEvent[i] = false;
00210 ROS_INFO("bREG %d", i);
00211 }
00212
00213 for(int i = 0; i < 3; i++){
00214 bRegisteredDirectionalArrows[i] = false;
00215 }
00216
00217
00218
00219
00220
00221
00222
00223
00224
00225
00226
00227
00228
00229
00230 vel_pub_ = nh_.advertise<geometry_msgs::Twist>(cmd_topic_vel_, 1);
00231
00232 ptz_pub_ = nh_.advertise<robotnik_msgs::ptz>(cmd_topic_ptz_, 1);
00233
00234
00235
00236 pad_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", 10, &SummitXLPad::padCallback, this);
00237
00238
00239 set_digital_outputs_client_ = nh_.serviceClient<robotnik_msgs::set_digital_output>(cmd_service_io_);
00240 bOutput1 = bOutput2 = false;
00241
00242
00243 setKinematicMode = nh_.serviceClient<robotnik_msgs::set_mode>(cmd_set_mode_);
00244
00245
00246 doHome = nh_.serviceClient<robotnik_msgs::home>(cmd_home_);
00247
00248
00249 updater_pad.setHardwareID("None");
00250
00251 min_freq_command = min_freq_joy = 5.0;
00252 max_freq_command = max_freq_joy = 50.0;
00253 sus_joy_freq = new diagnostic_updater::HeaderlessTopicDiagnostic("/joy", updater_pad,
00254 diagnostic_updater::FrequencyStatusParam(&min_freq_joy, &max_freq_joy, 0.1, 10));
00255
00256 pub_command_freq = new diagnostic_updater::HeaderlessTopicDiagnostic(cmd_topic_vel_.c_str(), updater_pad,
00257 diagnostic_updater::FrequencyStatusParam(&min_freq_command, &max_freq_command, 0.1, 10));
00258
00259
00260 bEnable = false;
00261 last_command_ = true;
00262 }
00263
00264
00265
00266
00267
00268
00269 void SummitXLPad::Update(){
00270 updater_pad.update();
00271 }
00272
00273
00274
00275 void SummitXLPad::padCallback(const sensor_msgs::Joy::ConstPtr& joy)
00276 {
00277 geometry_msgs::Twist vel;
00278 robotnik_msgs::ptz ptz;
00279 bool ptzEvent = false;
00280
00281 vel.linear.x = 0.0;
00282 vel.linear.y = 0.0;
00283 vel.linear.z = 0.0;
00284
00285 vel.angular.x = 0.0;
00286 vel.angular.y = 0.0;
00287 vel.angular.z = 0.0;
00288
00289 bEnable = (joy->buttons[dead_man_button_] == 1);
00290
00291
00292 if (joy->buttons[dead_man_button_] == 1) {
00293
00294
00295 if ( joy->buttons[speed_down_button_] == 1 ){
00296
00297 if(!bRegisteredButtonEvent[speed_down_button_])
00298 if(current_vel > 0.1){
00299 current_vel = current_vel - 0.1;
00300 bRegisteredButtonEvent[speed_down_button_] = true;
00301 ROS_INFO("Velocity: %f%%", current_vel*100.0);
00302 char buf[50]="\0";
00303 int percent = (int) (current_vel*100.0);
00304 sprintf(buf," %d percent", percent);
00305
00306 }
00307 }else{
00308 bRegisteredButtonEvent[speed_down_button_] = false;
00309 }
00310
00311 if (joy->buttons[speed_up_button_] == 1){
00312 if(!bRegisteredButtonEvent[speed_up_button_])
00313 if(current_vel < 0.9){
00314 current_vel = current_vel + 0.1;
00315 bRegisteredButtonEvent[speed_up_button_] = true;
00316 ROS_INFO("Velocity: %f%%", current_vel*100.0);
00317 char buf[50]="\0";
00318 int percent = (int) (current_vel*100.0);
00319 sprintf(buf," %d percent", percent);
00320
00321 }
00322
00323 }else{
00324 bRegisteredButtonEvent[speed_up_button_] = false;
00325 }
00326
00327
00328
00329
00330 vel.linear.x = current_vel*l_scale_*joy->axes[linear_x_];
00331 vel.linear.y = current_vel*l_scale_*joy->axes[linear_y_];
00332
00333
00334
00335 if(joystick_dead_zone_=="true")
00336 {
00337
00338 if(joy->axes[angular_] == 1.0 || joy->axes[angular_] == -1.0)
00339 {
00340
00341 vel.angular.x = current_vel*(a_scale_*joy->axes[angular_]);
00342 vel.angular.y = current_vel*(a_scale_*joy->axes[angular_]);
00343 vel.angular.z = current_vel*(a_scale_*joy->axes[angular_]);
00344
00345 vel.linear.z = 0.0;
00346 }
00347 else if (joy->axes[linear_z_] == 1.0 || joy->axes[linear_z_] == -1.0)
00348 {
00349 vel.linear.z = current_vel*l_scale_z_*joy->axes[linear_z_];
00350
00351
00352 vel.angular.x = 0.0;
00353 vel.angular.y = 0.0;
00354 vel.angular.z = 0.0;
00355 }
00356 else
00357 {
00358
00359 vel.angular.x = current_vel*(a_scale_*joy->axes[angular_]);
00360 vel.angular.y = current_vel*(a_scale_*joy->axes[angular_]);
00361 vel.angular.z = current_vel*(a_scale_*joy->axes[angular_]);
00362 vel.linear.z = current_vel*l_scale_z_*joy->axes[linear_z_];
00363 }
00364 }
00365 else
00366 {
00367 vel.angular.x = current_vel*(a_scale_*joy->axes[angular_]);
00368 vel.angular.y = current_vel*(a_scale_*joy->axes[angular_]);
00369 vel.angular.z = current_vel*(a_scale_*joy->axes[angular_]);
00370 vel.linear.z = current_vel*l_scale_z_*joy->axes[linear_z_];
00371 }
00372
00373
00374
00375
00376
00377
00378 if (joy->buttons[button_output_1_] == 1) {
00379
00380 if(!bRegisteredButtonEvent[button_output_1_]){
00381
00382 robotnik_msgs::set_digital_output write_do_srv;
00383 write_do_srv.request.output = output_1_;
00384 bOutput1=!bOutput1;
00385 write_do_srv.request.value = bOutput1;
00386 if(bEnable){
00387 set_digital_outputs_client_.call( write_do_srv );
00388 bRegisteredButtonEvent[button_output_1_] = true;
00389 }
00390 }
00391 }else{
00392 bRegisteredButtonEvent[button_output_1_] = false;
00393 }
00394
00395 if (joy->buttons[button_output_2_] == 1) {
00396
00397 if(!bRegisteredButtonEvent[button_output_2_]){
00398
00399 robotnik_msgs::set_digital_output write_do_srv;
00400 write_do_srv.request.output = output_2_;
00401 bOutput2=!bOutput2;
00402 write_do_srv.request.value = bOutput2;
00403
00404 if(bEnable){
00405 set_digital_outputs_client_.call( write_do_srv );
00406 bRegisteredButtonEvent[button_output_2_] = true;
00407 }
00408 }
00409 }else{
00410 bRegisteredButtonEvent[button_output_2_] = false;
00411 }
00412
00413
00414
00415
00416 if (joy->buttons[button_home_] == 1) {
00417 if (!bRegisteredButtonEvent[button_home_]) {
00418 robotnik_msgs::home home_srv;
00419 home_srv.request.request = true;
00420 if (bEnable) {
00421 ROS_INFO("SummitXLPad::padCallback - Home");
00422 doHome.call( home_srv );
00423 bRegisteredButtonEvent[button_home_] = true;
00424 }
00425 }
00426
00427 vel.angular.x = 0.0;
00428 vel.angular.y = 0.0;
00429 vel.angular.z = 0.0;
00430 vel.linear.x = 0.0;
00431 vel.linear.y = 0.0;
00432 }
00433 else {
00434 bRegisteredButtonEvent[button_home_]=false;
00435 }
00436
00437
00438
00439
00440 ptz.pan = ptz.tilt = ptz.zoom = 0.0;
00441 ptz.relative = true;
00442
00443 if(pad_type_=="ps4" || pad_type_=="logitechf710")
00444 {
00445 if (joy->axes[ptz_tilt_up_] == 1.0) {
00446 if(!bRegisteredDirectionalArrows[AXIS_PTZ_TILT_UP]){
00447 ptz.tilt = tilt_increment_;
00448
00449 bRegisteredDirectionalArrows[AXIS_PTZ_TILT_UP] = true;
00450 ptzEvent = true;
00451 }
00452 }else{
00453 bRegisteredDirectionalArrows[AXIS_PTZ_TILT_UP] = false;
00454 }
00455 if (joy->axes[ptz_tilt_down_] == -1.0) {
00456 if(!bRegisteredDirectionalArrows[AXIS_PTZ_TILT_DOWN]){
00457 ptz.tilt = -tilt_increment_;
00458
00459 bRegisteredDirectionalArrows[AXIS_PTZ_TILT_DOWN] = true;
00460 ptzEvent = true;
00461 }
00462 }else{
00463 bRegisteredDirectionalArrows[AXIS_PTZ_TILT_DOWN] = false;
00464 }
00465 if (joy->axes[ptz_pan_left_] == 1.0) {
00466 if(!bRegisteredDirectionalArrows[AXIS_PTZ_PAN_LEFT]){
00467 ptz.pan = -pan_increment_;
00468
00469 bRegisteredDirectionalArrows[AXIS_PTZ_PAN_LEFT] = true;
00470 ptzEvent = true;
00471 }
00472 }else{
00473 bRegisteredDirectionalArrows[AXIS_PTZ_PAN_LEFT] = false;
00474 }
00475 if (joy->axes[ptz_pan_right_] == -1.0) {
00476 if(!bRegisteredDirectionalArrows[AXIS_PTZ_PAN_RIGHT]){
00477 ptz.pan = pan_increment_;
00478
00479 bRegisteredDirectionalArrows[AXIS_PTZ_PAN_RIGHT] = true;
00480 ptzEvent = true;
00481 }
00482 }else{
00483 bRegisteredDirectionalArrows[AXIS_PTZ_PAN_RIGHT] = false;
00484 }
00485
00486 }else{
00487
00488
00489 if (joy->buttons[ptz_tilt_up_] == 1) {
00490 if(!bRegisteredButtonEvent[ptz_tilt_up_]){
00491 ptz.tilt = tilt_increment_;
00492
00493 bRegisteredButtonEvent[ptz_tilt_up_] = true;
00494 ptzEvent = true;
00495 }
00496 }else {
00497 bRegisteredButtonEvent[ptz_tilt_up_] = false;
00498 }
00499
00500 if (joy->buttons[ptz_tilt_down_] == 1) {
00501 if(!bRegisteredButtonEvent[ptz_tilt_down_]){
00502 ptz.tilt = -tilt_increment_;
00503
00504 bRegisteredButtonEvent[ptz_tilt_down_] = true;
00505 ptzEvent = true;
00506 }
00507 }else{
00508 bRegisteredButtonEvent[ptz_tilt_down_] = false;
00509 }
00510
00511
00512 if (joy->buttons[ptz_pan_left_] == 1) {
00513 if(!bRegisteredButtonEvent[ptz_pan_left_]){
00514 ptz.pan = -pan_increment_;
00515
00516 bRegisteredButtonEvent[ptz_pan_left_] = true;
00517 ptzEvent = true;
00518 }
00519 }else{
00520 bRegisteredButtonEvent[ptz_pan_left_] = false;
00521 }
00522
00523 if (joy->buttons[ptz_pan_right_] == 1) {
00524 if(!bRegisteredButtonEvent[ptz_pan_right_]){
00525 ptz.pan = pan_increment_;
00526
00527 bRegisteredButtonEvent[ptz_pan_right_] = true;
00528 ptzEvent = true;
00529 }
00530 }else{
00531 bRegisteredButtonEvent[ptz_pan_right_] = false;
00532 }
00533 }
00534
00535
00536 if (joy->buttons[ptz_zoom_wide_] == 1) {
00537 if(!bRegisteredButtonEvent[ptz_zoom_wide_]){
00538 ptz.zoom = -zoom_increment_;
00539
00540 bRegisteredButtonEvent[ptz_zoom_wide_] = true;
00541 ptzEvent = true;
00542 }
00543 }else{
00544 bRegisteredButtonEvent[ptz_zoom_wide_] = false;
00545 }
00546
00547 if (joy->buttons[ptz_zoom_tele_] == 1) {
00548 if(!bRegisteredButtonEvent[ptz_zoom_tele_]){
00549 ptz.zoom = zoom_increment_;
00550
00551 bRegisteredButtonEvent[ptz_zoom_tele_] = true;
00552 ptzEvent = true;
00553 }
00554 }else{
00555 bRegisteredButtonEvent[ptz_zoom_tele_] = false;
00556 }
00557
00558 if (joy->buttons[button_kinematic_mode_] == 1) {
00559
00560 if(!bRegisteredButtonEvent[button_kinematic_mode_]){
00561
00562 kinematic_mode_ += 1;
00563 if (kinematic_mode_ > 2) kinematic_mode_ = 1;
00564 ROS_INFO("SummitXLJoy::joyCallback: Kinematic Mode %d ", kinematic_mode_);
00565
00566 robotnik_msgs::set_mode set_mode_srv;
00567 set_mode_srv.request.mode = kinematic_mode_;
00568 setKinematicMode.call( set_mode_srv );
00569 bRegisteredButtonEvent[button_kinematic_mode_] = true;
00570 }
00571 }else{
00572 bRegisteredButtonEvent[button_kinematic_mode_] = false;
00573 }
00574
00575
00576
00577 }
00578 else {
00579 vel.angular.x = 0.0; vel.angular.y = 0.0; vel.angular.z = 0.0;
00580 vel.linear.x = 0.0; vel.linear.y = 0.0; vel.linear.z = 0.0;
00581 }
00582
00583 sus_joy_freq->tick();
00584
00585
00586
00587 if(bEnable){
00588 if (ptzEvent) ptz_pub_.publish(ptz);
00589 vel_pub_.publish(vel);
00590 pub_command_freq->tick();
00591 last_command_ = true;
00592 }
00593
00594
00595 if(!bEnable && last_command_){
00596 if (ptzEvent) ptz_pub_.publish(ptz);
00597
00598 vel.angular.x = 0.0; vel.angular.y = 0.0; vel.angular.z = 0.0;
00599 vel.linear.x = 0.0; vel.linear.y = 0.0; vel.linear.z = 0.0;
00600 vel_pub_.publish(vel);
00601 pub_command_freq->tick();
00602 last_command_ = false;
00603 }
00604 }
00605
00606
00607 int main(int argc, char** argv)
00608 {
00609 ros::init(argc, argv, "summit_xl_pad");
00610 SummitXLPad summit_xl_pad;
00611
00612 ros::Rate r(50.0);
00613
00614 while( ros::ok() ){
00615
00616 summit_xl_pad.Update();
00617 ros::spinOnce();
00618 r.sleep();
00619 }
00620 }
00621