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 #include <ros/ros.h>
00035 #include <sensor_msgs/Joy.h>
00036 #include <geometry_msgs/Twist.h>
00037 #include <std_msgs/Int32.h>
00038 #include <unistd.h>
00039 #include <vector>
00040 #include <robotnik_msgs/enable_disable.h>
00041 #include <robotnik_msgs/set_digital_output.h>
00042 #include "diagnostic_msgs/DiagnosticStatus.h"
00043 #include "diagnostic_updater/diagnostic_updater.h"
00044 #include "diagnostic_updater/update_functions.h"
00045 #include "diagnostic_updater/DiagnosticStatusWrapper.h"
00046 #include "diagnostic_updater/publisher.h"
00047 #include "ackermann_msgs/AckermannDriveStamped.h"
00048 #include <std_srvs/Empty.h>
00049 #include "robotnik_msgs/set_mode.h"
00050 #include "robotnik_msgs/get_mode.h"
00051
00052 #define DEFAULT_MAX_LINEAR_SPEED 3.0 //m/s
00053 #define DEFAULT_MAX_ANGULAR_POSITION 2.0 // rads/s
00054
00055 #define MAX_NUM_OF_BUTTONS 16
00056 #define MAX_NUM_OF_AXES 8
00057 #define MAX_NUM_OF_BUTTONS_PS3 19
00058 #define MAX_NUM_OF_AXES_PS3 20
00059
00060 #define DEFAULT_NUM_OF_BUTTONS 16
00061 #define DEFAULT_NUM_OF_AXES 8
00062
00063 #define DEFAULT_AXIS_LINEAR_X 1
00064 #define DEFAULT_AXIS_ANGULAR 2
00065 #define DEFAULT_SCALE_LINEAR 1.0
00066 #define DEFAULT_SCALE_ANGULAR 1.0
00067
00068 #define DEFAULT_JOY "/joy"
00069 #define DEFAULT_HZ 50.0
00070
00071
00073 class Button{
00074 int iPressed;
00075 bool bReleased;
00076
00077 public:
00078
00079 Button(){
00080 iPressed = 0;
00081 bReleased = false;
00082 }
00084 void Press(int value){
00085 if(iPressed and !value){
00086 bReleased = true;
00087
00088 }else if(bReleased and value)
00089 bReleased = false;
00090
00091 iPressed = value;
00092
00093 }
00094
00095 int IsPressed(){
00096 return iPressed;
00097 }
00098
00099 bool IsReleased(){
00100 bool b = bReleased;
00101 bReleased = false;
00102 return b;
00103 }
00104 };
00105
00106 class RbcarJoy
00107 {
00108 public:
00109 RbcarJoy();
00110
00111 void ControlLoop();
00112 int SetStateMode(int state, int arm_mode, int platform_mode);
00113
00114 private:
00115
00116 void joyCallback(const sensor_msgs::Joy::ConstPtr& joy);
00117
00118 char * StateToString(int state);
00119 int SwitchToState(int new_state);
00120
00121 void PublishState();
00123 bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res );
00124 void Update();
00125
00126
00127 private:
00128 ros::NodeHandle nh_;
00129
00130 int axis_linear_speed_, axis_angular_position_;
00131 double l_scale_, a_scale_;
00132 double current_speed_lvl;
00134 double max_linear_speed_, max_angular_position_;
00136 double desired_freq_;
00137
00138
00140 ros::Publisher vel_pub_;
00142 ros::Subscriber joy_sub_;
00144 std::string joy_topic_;
00146 std::string cmd_topic_vel;
00148 std::string cmd_service_io_;
00150 std::string topic_state_;
00152 ros::Publisher state_pub_;
00153
00154
00156 ros::ServiceServer enable_disable_srv_;
00157 ros::ServiceClient set_digital_outputs_client_;
00158
00159
00161 int num_of_buttons_;
00162 int num_of_axes_;
00163
00165 std::vector<float> fAxes;
00167 std::vector<Button> vButtons;
00169 int button_dead_man_;
00171 int button_speed_up_, button_speed_down_;
00172 int output_1_, output_2_;
00173 bool bOutput1, bOutput2;
00175 int ptz_tilt_up_, ptz_tilt_down_, ptz_pan_right_, ptz_pan_left_;
00177 std::string cmd_service_ptz_;
00179 int button_kinematic_mode_;
00181 int kinematic_mode_;
00183 ros::ServiceClient setKinematicMode;
00185 std::string cmd_set_mode_;
00186
00187
00189 diagnostic_updater::HeaderlessTopicDiagnostic *pub_command_freq;
00191 diagnostic_updater::HeaderlessTopicDiagnostic *sus_joy_freq;
00193 diagnostic_updater::Updater updater_pad;
00195 double min_freq_command, min_freq_joy;
00197 double max_freq_command, max_freq_joy;
00199 bool bEnable;
00200 };
00201
00202 RbcarJoy::RbcarJoy():
00203 axis_linear_speed_(1),
00204 axis_angular_position_(2)
00205 {
00206 current_speed_lvl = 0.1;
00207
00208 nh_.param("num_of_buttons", num_of_buttons_, DEFAULT_NUM_OF_BUTTONS);
00209 nh_.param("num_of_axes", num_of_axes_, DEFAULT_NUM_OF_AXES);
00210 nh_.param("desired_freq", desired_freq_, DEFAULT_HZ);
00211
00212 if(num_of_axes_ > MAX_NUM_OF_AXES){
00213 num_of_axes_ = MAX_NUM_OF_AXES;
00214 ROS_INFO("RbcarJoy::RbcarJoy: Limiting the max number of axes to %d", MAX_NUM_OF_AXES);
00215 }
00216 if(num_of_buttons_ > MAX_NUM_OF_BUTTONS){
00217 num_of_buttons_ = MAX_NUM_OF_BUTTONS;
00218 ROS_INFO("RbcarJoy::RbcarJoy: Limiting the max number of buttons to %d", MAX_NUM_OF_BUTTONS);
00219 }
00220
00221 nh_.param("topic_joy", joy_topic_, std::string(DEFAULT_JOY));
00222
00223
00224
00225 nh_.param("cmd_topic_vel", cmd_topic_vel, std::string("/rbcar_robot_control/command"));
00226
00227 nh_.param("button_dead_man", button_dead_man_, button_dead_man_);
00228 nh_.param("button_speed_up", button_speed_up_, button_speed_up_);
00229 nh_.param("button_speed_down", button_speed_down_, button_speed_down_);
00230 nh_.param("max_angular_position", max_angular_position_, DEFAULT_MAX_ANGULAR_POSITION);
00231 nh_.param("max_linear_speed_", max_linear_speed_, DEFAULT_MAX_LINEAR_SPEED);
00232 nh_.param("axis_linear_speed", axis_linear_speed_, DEFAULT_AXIS_LINEAR_X);
00233 nh_.param("axis_angular_position", axis_angular_position_, DEFAULT_AXIS_ANGULAR);
00234 ROS_INFO("axis_linear_speed_ = %d, axis_angular = %d", axis_linear_speed_, axis_angular_position_);
00235 ROS_INFO("max_linear_speed = %lf, max_angular_speed = %lf", max_linear_speed_, max_angular_position_);
00236
00237
00238 nh_.param("cmd_service_io", cmd_service_io_, cmd_service_io_);
00239 nh_.param("output_1", output_1_, output_1_);
00240 nh_.param("output_2", output_2_, output_2_);
00241 nh_.param("topic_state", topic_state_, std::string("/rbcar_joystick/state"));
00242
00243
00244 nh_.param("cmd_service_ptz", cmd_service_ptz_, cmd_service_ptz_);
00245 nh_.param("button_ptz_tilt_up", ptz_tilt_up_, ptz_tilt_up_);
00246 nh_.param("button_ptz_tilt_down", ptz_tilt_down_, ptz_tilt_down_);
00247 nh_.param("button_ptz_pan_right", ptz_pan_right_, ptz_pan_right_);
00248 nh_.param("button_ptz_pan_left", ptz_pan_left_, ptz_pan_left_);
00249
00250
00251 nh_.param("button_kinematic_mode", button_kinematic_mode_, button_kinematic_mode_);
00252 nh_.param("cmd_service_set_mode", cmd_set_mode_, cmd_set_mode_);
00253 kinematic_mode_ = 1;
00254
00255 ROS_INFO("RbcarJoy num_of_buttons_ = %d, axes = %d, topic controller: %s, hz = %.2lf", num_of_buttons_, num_of_axes_, cmd_topic_vel.c_str(), desired_freq_);
00256
00257 for(int i = 0; i < MAX_NUM_OF_BUTTONS_PS3; i++){
00258 Button b;
00259 vButtons.push_back(b);
00260 }
00261
00262 for(int i = 0; i < MAX_NUM_OF_AXES_PS3; i++){
00263 fAxes.push_back(0.0);
00264 }
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280
00281 this->vel_pub_ = nh_.advertise<ackermann_msgs::AckermannDriveStamped>(this->cmd_topic_vel, 1);
00282
00283
00284 joy_sub_ = nh_.subscribe<sensor_msgs::Joy>(joy_topic_, 1, &RbcarJoy::joyCallback, this);
00285
00286
00287 set_digital_outputs_client_ = nh_.serviceClient<robotnik_msgs::set_digital_output>(cmd_service_io_);
00288
00289 bOutput1 = bOutput2 = false;
00290
00291
00292 updater_pad.setHardwareID("RbcarJoystick");
00293
00294 min_freq_command = min_freq_joy = 5.0;
00295 max_freq_command = max_freq_joy = 50.0;
00296 sus_joy_freq = new diagnostic_updater::HeaderlessTopicDiagnostic("/joy", updater_pad,
00297 diagnostic_updater::FrequencyStatusParam(&min_freq_joy, &max_freq_joy, 0.1, 10));
00298
00299 pub_command_freq = new diagnostic_updater::HeaderlessTopicDiagnostic(cmd_topic_vel.c_str(), updater_pad,
00300 diagnostic_updater::FrequencyStatusParam(&min_freq_command, &max_freq_command, 0.1, 10));
00301
00302
00303 enable_disable_srv_ = nh_.advertiseService("/rbcar_joystick/enable_disable", &RbcarJoy::EnableDisable, this);
00304
00305 bEnable = true;
00306
00307
00308
00309 }
00310
00311
00312
00313
00314
00315
00316 void RbcarJoy::Update(){
00317 PublishState();
00318 }
00319
00321 void RbcarJoy::PublishState(){
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331 }
00332
00333
00334
00335
00336 bool RbcarJoy::EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res )
00337 {
00338 bEnable = req.value;
00339
00340 ROS_INFO("RbcarJoy::EnablaDisable: Setting to %d", req.value);
00341 res.ret = true;
00342 return true;
00343 }
00344
00345 void RbcarJoy::joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
00346 {
00347
00348
00349 for(int i = 0; i < joy->axes.size(); i++){
00350 this->fAxes[i] = joy->axes[i];
00351 }
00352 for(int i = 0; i < joy->buttons.size(); i++){
00353 this->vButtons[i].Press(joy->buttons[i]);
00354 }
00355
00356
00357 }
00358
00360 void RbcarJoy::ControlLoop(){
00361
00362 double desired_linear_speed = 0.0, desired_angular_position = 0.0;
00363 ackermann_msgs::AckermannDriveStamped ref_msg;
00364
00365 ros::Rate r(desired_freq_);
00366
00367 while(ros::ok()) {
00368
00369 Update();
00370
00371 if(bEnable){
00372
00373 if(vButtons[button_dead_man_].IsPressed()){
00374 ref_msg.header.stamp = ros::Time::now();
00375 ref_msg.drive.jerk = 0.0;
00376 ref_msg.drive.acceleration = 0.0;
00377 ref_msg.drive.steering_angle_velocity = 0.0;
00378
00379 desired_linear_speed = max_linear_speed_ * current_speed_lvl * fAxes[axis_linear_speed_];
00380 desired_angular_position = max_angular_position_ * fAxes[axis_angular_position_];
00381
00382
00383
00384 ref_msg.drive.steering_angle = desired_angular_position;
00385 ref_msg.drive.speed = desired_linear_speed;
00386
00387
00388 vel_pub_.publish(ref_msg);
00389
00390 if(vButtons[button_speed_up_].IsReleased()){
00391 current_speed_lvl += 0.1;
00392 if(current_speed_lvl > 1.0)
00393 current_speed_lvl = 1.0;
00394 }
00395 if(vButtons[button_speed_down_].IsReleased()){
00396 current_speed_lvl -= 0.1;
00397 if(current_speed_lvl < 0.0)
00398 current_speed_lvl = 0.0;
00399 }
00400
00401 }else if(vButtons[button_dead_man_].IsReleased()){
00402 ref_msg.header.stamp = ros::Time::now();
00403 ref_msg.drive.jerk = 0.0;
00404 ref_msg.drive.acceleration = 0.0;
00405 ref_msg.drive.steering_angle_velocity = 0.0;
00406
00407 ref_msg.drive.steering_angle = 0.0;
00408 ref_msg.drive.speed = 0.0;
00409
00410 vel_pub_.publish(ref_msg);
00411 }
00412 }
00413
00414 ros::spinOnce();
00415 r.sleep();
00416 }
00417 }
00418
00420 int main(int argc, char** argv)
00421 {
00422 ros::init(argc, argv, "rbcar_joystick");
00423 RbcarJoy joy;
00424
00425 joy.ControlLoop();
00426
00427 }
00428
00429