Go to the documentation of this file.
45 #include <sensor_msgs/JointState.h>
46 #include <std_msgs/Float64MultiArray.h>
48 #define KEYCODE_a 0x61
49 #define KEYCODE_b 0x62
50 #define KEYCODE_c 0x63
51 #define KEYCODE_d 0x64
52 #define KEYCODE_e 0x65
53 #define KEYCODE_f 0x66
54 #define KEYCODE_g 0x67
55 #define KEYCODE_h 0x68
56 #define KEYCODE_i 0x69
57 #define KEYCODE_j 0x6a
58 #define KEYCODE_k 0x6b
59 #define KEYCODE_l 0x6c
60 #define KEYCODE_m 0x6d
61 #define KEYCODE_n 0x6e
62 #define KEYCODE_o 0x6f
63 #define KEYCODE_p 0x70
64 #define KEYCODE_q 0x71
65 #define KEYCODE_r 0x72
66 #define KEYCODE_s 0x73
67 #define KEYCODE_t 0x74
68 #define KEYCODE_u 0x75
69 #define KEYCODE_v 0x76
70 #define KEYCODE_w 0x77
71 #define KEYCODE_x 0x78
72 #define KEYCODE_y 0x79
73 #define KEYCODE_z 0x7a
74 #define KEYCODE_ESCAPE 0x1B
77 struct termios cooked,
raw;
81 tcsetattr(
kfd, TCSANOW, &cooked);
90 std::cout <<
"init " << std::endl;
104 if (msg->position.size() != 7)
112 cmd_.data = msg->position;
128 tcgetattr(
kfd, &cooked);
129 memcpy(&
raw, &cooked,
sizeof(
struct termios));
130 raw.c_lflag &= ~(ICANON | ECHO);
134 tcsetattr(
kfd, TCSANOW, &
raw);
136 puts(
"Reading from keyboard");
137 puts(
"---------------------------");
138 puts(
"Use 'QA' to for joint 1");
139 puts(
"Use 'WS' to for joint 2");
140 puts(
"Use 'ED' to for joint 3");
141 puts(
"Use 'RF' to for joint 4");
142 puts(
"Use 'TG' to for joint 5");
143 puts(
"Use 'YH' to for joint 6");
144 puts(
"Use 'UJ' to for joint 7");
147 double delta_dist = 0.005;
152 if (read(
kfd, &c, 1) < 0)
162 cmd_.data[0] =
cmd_.data[0] + delta_dist;
165 cmd_.data[0] =
cmd_.data[0] - delta_dist;
169 cmd_.data[1] =
cmd_.data[1] + delta_dist;
172 cmd_.data[1] =
cmd_.data[1] - delta_dist;
176 cmd_.data[2] =
cmd_.data[2] + delta_dist;
179 cmd_.data[2] =
cmd_.data[2] - delta_dist;
183 cmd_.data[3] =
cmd_.data[3] + delta_dist;
186 cmd_.data[3] =
cmd_.data[3] - delta_dist;
190 cmd_.data[4] =
cmd_.data[4] + delta_dist;
193 cmd_.data[4] =
cmd_.data[4] - delta_dist;
197 cmd_.data[5] =
cmd_.data[5] + delta_dist;
200 cmd_.data[5] =
cmd_.data[5] - delta_dist;
204 cmd_.data[6] =
cmd_.data[6] + delta_dist;
207 cmd_.data[6] =
cmd_.data[6] - delta_dist;
211 std::cout << std::endl;
212 std::cout <<
"Exiting " << std::endl;
217 std::cout <<
"CODE: " << c << std::endl;
242 std_msgs::Float64MultiArray
cmd_;
246 int main(
int argc,
char** argv)
248 ros::init(argc, argv,
"joints_teleop_keyboard");
249 signal(SIGINT,
quit);
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void stateCallback(const sensor_msgs::JointStateConstPtr &msg)
bool has_recieved_joints_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std_msgs::Float64MultiArray cmd_
#define ROS_ERROR_STREAM_NAMED(name, args)
ros::Publisher joints_pub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Subscriber joints_sub_
struct termios cooked raw
int main(int argc, char **argv)