aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-10-22 13:28:53 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-10-22 13:28:53 +0200
commit3a26708203cbdc5ca8dd0e6b00435f204b9fd2e8 (patch)
tree317863d434ede4f62c813ab3bcda7d08babcc6a6
parent3932bad137dcb908c4b4b563a996a7205a844b3f (diff)
downloadpx4-firmware-3a26708203cbdc5ca8dd0e6b00435f204b9fd2e8.tar.gz
px4-firmware-3a26708203cbdc5ca8dd0e6b00435f204b9fd2e8.tar.bz2
px4-firmware-3a26708203cbdc5ca8dd0e6b00435f204b9fd2e8.zip
Resolved wrong TX drop display
-rw-r--r--apps/commander/commander.c6
-rw-r--r--apps/mavlink/mavlink.c18
-rw-r--r--apps/mavlink/mavlink_bridge_header.h8
-rw-r--r--mavlink/include/mavlink/v1.0/mavlink_helpers.h4
-rw-r--r--mavlink/include/mavlink/v1.0/protocol.h2
5 files changed, 37 insertions, 1 deletions
diff --git a/apps/commander/commander.c b/apps/commander/commander.c
index ef508e759..50d0a7f13 100644
--- a/apps/commander/commander.c
+++ b/apps/commander/commander.c
@@ -728,6 +728,9 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta
/* result of the command */
uint8_t result = MAV_RESULT_UNSUPPORTED;
+ /* announce command handling */
+ ioctl(buzzer, TONE_SET_ALARM, 1);
+
/* supported command handling start */
@@ -907,6 +910,9 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta
default: {
mavlink_log_critical(mavlink_fd, "[commander] refusing unsupported command");
result = MAV_RESULT_UNSUPPORTED;
+ usleep(200000);
+ /* announce command rejection */
+ ioctl(buzzer, TONE_SET_ALARM, 4);
}
break;
}
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index fd02eb363..2ac803ce0 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -454,6 +454,24 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, uint8_t *ch, int length)
write(uart, ch, (size_t)(sizeof(uint8_t) * length));
}
+/*
+ * Internal function to give access to the channel status for each channel
+ */
+mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
+{
+ static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
+ return &m_mavlink_status[chan];
+}
+
+/*
+ * Internal function to give access to the channel buffer for each channel
+ */
+mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
+{
+ static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
+ return &m_mavlink_buffer[chan];
+}
+
void mavlink_update_system(void)
{
static bool initialized = false;
diff --git a/apps/mavlink/mavlink_bridge_header.h b/apps/mavlink/mavlink_bridge_header.h
index 8d34c3924..de8bc4ae7 100644
--- a/apps/mavlink/mavlink_bridge_header.h
+++ b/apps/mavlink/mavlink_bridge_header.h
@@ -43,9 +43,12 @@
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
-//use efficient approach, see mavlink_helpers.h
+/* use efficient approach, see mavlink_helpers.h */
#define MAVLINK_SEND_UART_BYTES mavlink_send_uart_bytes
+#define MAVLINK_GET_CHANNEL_BUFFER mavlink_get_channel_buffer
+#define MAVLINK_GET_CHANNEL_STATUS mavlink_get_channel_status
+
#include "v1.0/mavlink_types.h"
#include <unistd.h>
@@ -70,4 +73,7 @@ extern mavlink_system_t mavlink_system;
*/
extern void mavlink_send_uart_bytes(mavlink_channel_t chan, uint8_t *ch, int length);
+mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
+mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan);
+
#endif /* MAVLINK_BRIDGE_HEADER_H */
diff --git a/mavlink/include/mavlink/v1.0/mavlink_helpers.h b/mavlink/include/mavlink/v1.0/mavlink_helpers.h
index f0f3404a2..f41b36883 100644
--- a/mavlink/include/mavlink/v1.0/mavlink_helpers.h
+++ b/mavlink/include/mavlink/v1.0/mavlink_helpers.h
@@ -12,15 +12,18 @@
/*
* Internal function to give access to the channel status for each channel
*/
+#ifndef MAVLINK_GET_CHANNEL_STATUS
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
{
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
return &m_mavlink_status[chan];
}
+#endif
/*
* Internal function to give access to the channel buffer for each channel
*/
+#ifndef MAVLINK_GET_CHANNEL_BUFFER
MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
{
@@ -35,6 +38,7 @@ MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
#endif
return &m_mavlink_buffer[chan];
}
+#endif
/**
* @brief Reset the status of a channel.
diff --git a/mavlink/include/mavlink/v1.0/protocol.h b/mavlink/include/mavlink/v1.0/protocol.h
index 019ae5fc4..64dc22229 100644
--- a/mavlink/include/mavlink/v1.0/protocol.h
+++ b/mavlink/include/mavlink/v1.0/protocol.h
@@ -42,7 +42,9 @@
#endif // MAVLINK_SEPARATE_HELPERS
/* always include the prototypes to ensure we don't get out of sync */
+#ifndef MAVLINK_GET_CHANNEL_STATUS
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
+#endif
MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,