[mavlink] configurable device

This commit is contained in:
Felix Ruess
2014-12-08 14:59:37 +01:00
parent b8ac2ef752
commit d93591f439
3 changed files with 17 additions and 3 deletions
+11
View File
@@ -3,6 +3,8 @@
<module name="datalink"> <module name="datalink">
<doc> <doc>
<description>Basic MAVLink implementation</description> <description>Basic MAVLink implementation</description>
<configure name="MAVLINK_PORT" value="UARTx|UDPx" description="The port device to use for mavlink"/>
<configure name="MAVLINK_BAUD" value="B57600" description="Baud rate if MAVLINK_PORT is a UART"/>
</doc> </doc>
<header> <header>
<file name="mavlink.h"/> <file name="mavlink.h"/>
@@ -14,5 +16,14 @@
<makefile> <makefile>
<file name="mavlink.c"/> <file name="mavlink.c"/>
<raw>
MAVLINK_PORT ?= UART1
MAVLINK_BAUD ?= B57600
MAVLINK_PORT_LOWER=$(shell echo $(MAVLINK_PORT) | tr A-Z a-z)
MAVLINK_PORT_UPPER=$(shell echo $(MAVLINK_PORT) | tr a-z A-Z)
</raw>
<define name="MAVLINK_DEV" value="$(MAVLINK_PORT_UPPER)"/>
<define name="USE_$(MAVLINK_PORT_UPPER)"/>
<define name="$(MAVLINK_PORT_UPPER)_BAUD" value="$(MAVLINK_BAUD)"/>
</makefile> </makefile>
</module> </module>
+3 -2
View File
@@ -102,7 +102,7 @@ void mavlink_event(void)
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: { case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: {
mavlink_rc_channels_override_t cmd; mavlink_rc_channels_override_t cmd;
mavlink_msg_rc_channels_override_decode(&msg, &cmd); mavlink_msg_rc_channels_override_decode(&msg, &cmd);
#if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK
uint8_t thrust = (cmd.chan3_raw - 950) * 127 / 1100; uint8_t thrust = (cmd.chan3_raw - 950) * 127 / 1100;
int8_t roll = -(cmd.chan1_raw - 1500) * 255 / 1100 / 2; int8_t roll = -(cmd.chan1_raw - 1500) * 255 / 1100 / 2;
int8_t pitch = -(cmd.chan2_raw - 1500) * 255 / 1100 / 2; int8_t pitch = -(cmd.chan2_raw - 1500) * 255 / 1100 / 2;
@@ -110,6 +110,7 @@ void mavlink_event(void)
parse_rc_4ch_datalink(0, thrust, roll, pitch, yaw); parse_rc_4ch_datalink(0, thrust, roll, pitch, yaw);
//printf("RECEIVED: RC Channel Override for: %d/%d: throttle: %d; roll: %d; pitch: %d; yaw: %d;\r\n", //printf("RECEIVED: RC Channel Override for: %d/%d: throttle: %d; roll: %d; pitch: %d; yaw: %d;\r\n",
// cmd.target_system, cmd.target_component, thrust, roll, pitch, yaw); // cmd.target_system, cmd.target_component, thrust, roll, pitch, yaw);
#endif
break; break;
} }
@@ -159,7 +160,7 @@ void mavlink_event(void)
default: default:
//Do nothing //Do nothing
printf("Received message with id: %d\r\n", msg.msgid); //printf("Received message with id: %d\r\n", msg.msgid);
break; break;
} }
} }
+2
View File
@@ -42,7 +42,9 @@
*/ */
extern mavlink_system_t mavlink_system; extern mavlink_system_t mavlink_system;
#ifndef MAVLINK_DEV
#define MAVLINK_DEV UDP0 #define MAVLINK_DEV UDP0
#endif
/* /*
* The MAVLink link description * The MAVLink link description