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 #include <ros/ros.h>
00031 #include <geometry_msgs/Twist.h>
00032 #include <sensor_msgs/Joy.h>
00033 #include "kurt3d/Scan.h"
00034 #include <sensor_msgs/JointState.h>
00035
00036 #define RAD(GRAD) ((GRAD * (float)M_PI) / (float)180)
00037
00038 double max_vel_x, max_rotational_vel;
00039 ros::Publisher vel_pub;
00040 double speed_multiplier;
00041 static ros::ServiceClient client;
00042 ros::Publisher servo_pub;
00043
00044 static double min_pos[5] =
00045 {
00046 RAD(-50.0),
00047 RAD(-65.0),
00048 RAD(-65.0),
00049 RAD(-50.0),
00050 RAD(-65.0)
00051 };
00052 static double max_pos[5] =
00053 {
00054 RAD(60.0),
00055 RAD(45.0),
00056 RAD(45.0),
00057 RAD(60.0),
00058 RAD(45.0)
00059 };
00060
00061 void ps3joyCallback(const sensor_msgs::Joy::ConstPtr& joy)
00062 {
00063 geometry_msgs::Twist vel;
00064 if (joy->buttons[8] == 1)
00065 {
00066 speed_multiplier = 1.0;
00067 }
00068 else if (true)
00069 {
00070 speed_multiplier = 0.5 + (0.5 * joy->axes[3]);
00071 }
00072 else
00073 {
00074 speed_multiplier = 0.5;
00075 }
00076
00077
00078 if (joy->buttons[4] || joy->buttons[5] ||
00079 joy->buttons[6] || joy->buttons[7])
00080 {
00081
00082
00083 vel.linear.x = max_vel_x * (joy->axes[4] * -1.0 + joy->axes[6]) * speed_multiplier;
00084 vel.angular.z = max_rotational_vel * (joy->axes[7] * -1.0 + joy->axes[5]) * speed_multiplier;
00085 }
00086
00087 if (joy->buttons[12])
00088 {
00089 kurt3d::Scan srv;
00090
00091 if (client.call(srv))
00092 {
00093 ROS_INFO("Scan finished");
00094 }
00095 else
00096 {
00097 ROS_ERROR("Failed to call laserscanner_node service");
00098 }
00099
00100 }
00101 if(joy->buttons[10])
00102 {
00103 sensor_msgs::JointState msg;
00104 msg.name.resize(2);
00105 msg.position.resize(2);
00106 msg.velocity.resize(2);
00107 msg.effort.resize(2);
00108 msg.name[0] = "servo_1_b_to_wing_1_b";
00109 msg.name[1] = "servo_1_a_to_wing_1_a";
00110
00111 msg.position[0] = (((joy->axes[2]+1.0) / 2.0) * (max_pos[2]-min_pos[2])) + min_pos[2];
00112 msg.position[1] = (((joy->axes[3]*-1.0+1.0) / 2.0) * (max_pos[1]-min_pos[1])) + min_pos[1];
00113
00114 servo_pub.publish(msg);
00115 }
00116 if(joy->buttons[11])
00117 {
00118 sensor_msgs::JointState msg;
00119 msg.name.resize(2);
00120 msg.position.resize(2);
00121 msg.velocity.resize(2);
00122 msg.effort.resize(2);
00123 msg.name[0] = "servo_2_b_to_wing_2_b";
00124 msg.name[1] = "servo_2_a_to_wing_2_a";
00125
00126 msg.position[0] = (((joy->axes[2]+1.0) / 2.0) * (max_pos[4]-min_pos[4])) + min_pos[4];
00127 msg.position[1] = (((joy->axes[3]+1.0) / 2.0) * (max_pos[3]-min_pos[3])) + min_pos[3];
00128
00129 servo_pub.publish(msg);
00130 }
00131 else
00132 {
00133 vel.linear.x = max_vel_x * joy->axes[1] * speed_multiplier;
00134 vel.angular.z = max_rotational_vel * joy->axes[0] * speed_multiplier;
00135 }
00136 vel_pub.publish(vel);
00137 }
00138
00139 int main(int argc, char** argv)
00140 {
00141 ros::init(argc, argv, "ps3joy_kurt3d");
00142
00143 ros::NodeHandle nh;
00144 ros::NodeHandle nh_ns("~");
00145
00146 nh_ns.param("max_vel_x", max_vel_x, 1.5);
00147 nh_ns.param("max_rotational_vel", max_rotational_vel, 3.0);
00148
00149 vel_pub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00150 ros::Subscriber ps3joy_sub = nh.subscribe("joy", 10, ps3joyCallback);
00151
00152 ROS_INFO("Waiting for [laserscanner_node] to be advertised");
00153 ros::service::waitForService("assemble_scans2");
00154 ROS_INFO("Found laserscanner_node! Starting the ps3joy_kurt3d");
00155 client = nh.serviceClient<kurt3d::Scan>("laserscanner_node");
00156
00157 servo_pub = nh.advertise<sensor_msgs::JointState>("servo_control", 1);
00158
00159 ros::spin();
00160 }
00161