Skip to content

Commit 21d7e4f

Browse files
committed
Merge pull request ArduPilot#8 from tumbili/serial_device
read serial device to obtain manual control setpoint
2 parents 3db5f3b + 3a79679 commit 21d7e4f

File tree

1 file changed

+46
-8
lines changed

1 file changed

+46
-8
lines changed

src/modules/simulator/simulator_mavlink.cpp

Lines changed: 46 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@ using namespace simulator;
4040

4141
#define SEND_INTERVAL 1000
4242
#define UDP_PORT 14550
43+
#define PIXHAWK_DEVICE "/dev/ttyACM0"
4344

4445
static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
4546
static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
@@ -308,29 +309,49 @@ void Simulator::updateSamples()
308309
pthread_create(&sender_thread, &sender_thread_attr, Simulator::sending_trampoline, NULL);
309310
pthread_attr_destroy(&sender_thread_attr);
310311

311-
struct pollfd socket_fds;
312-
socket_fds.fd = _fd;
313-
socket_fds.events = POLLIN;
312+
// setup serial connection to autopilot (used to get manual controls)
313+
int serial_fd = open(PIXHAWK_DEVICE, O_RDWR);
314+
315+
if (serial_fd < 0) {
316+
PX4_WARN("failed to open %s\n", PIXHAWK_DEVICE);
317+
}
318+
319+
// tell the device to stream some messages
320+
char command[] = "\nsh /etc/init.d/rc.usb\n";
321+
int w = ::write(serial_fd, command, sizeof(command));
322+
323+
if (w <= 0) {
324+
PX4_WARN("failed to send streaming command to %s\n", PIXHAWK_DEVICE);
325+
}
326+
327+
char serial_buf[1024];
328+
329+
struct pollfd fds[2];
330+
fds[0].fd = _fd;
331+
fds[0].events = POLLIN;
332+
fds[1].fd = serial_fd;
333+
fds[1].events = POLLIN;
314334

315335
int len = 0;
316336
// wait for new mavlink messages to arrive
317337
while (true) {
318338

319-
int socket_pret = ::poll(&socket_fds, (size_t)1, 100);
339+
int pret = ::poll(&fds[0], (sizeof(fds)/sizeof(fds[0])), 100);
320340

321341
//timed out
322-
if (socket_pret == 0)
342+
if (pret == 0)
323343
continue;
324344

325345
// this is undesirable but not much we can do
326-
if (socket_pret < 0) {
327-
PX4_WARN("poll error %d, %d", socket_pret, errno);
346+
if (pret < 0) {
347+
PX4_WARN("poll error %d, %d", pret, errno);
328348
// sleep a bit before next try
329349
usleep(100000);
330350
continue;
331351
}
332352

333-
if (socket_fds.revents & POLLIN) {
353+
// got data from simulator
354+
if (fds[0].revents & POLLIN) {
334355
len = recvfrom(_fd, _buf, sizeof(_buf), 0, (struct sockaddr *)&_srcaddr, &_addrlen);
335356
if (len > 0) {
336357
mavlink_message_t msg;
@@ -346,6 +367,23 @@ void Simulator::updateSamples()
346367
}
347368
}
348369

370+
// got data from PIXHAWK
371+
if (fds[1].revents & POLLIN) {
372+
len = ::read(serial_fd, serial_buf, sizeof(serial_buf));
373+
if (len > 0) {
374+
mavlink_message_t msg;
375+
mavlink_status_t status;
376+
for (int i = 0; i < len; ++i)
377+
{
378+
if (mavlink_parse_char(MAVLINK_COMM_0, serial_buf[i], &msg, &status))
379+
{
380+
// have a message, handle it
381+
handle_message(&msg);
382+
}
383+
}
384+
}
385+
}
386+
349387
// publish these messages so that attitude estimator does not complain
350388
hrt_abstime time_last = hrt_absolute_time();
351389
baro.timestamp = time_last;

0 commit comments

Comments
 (0)