double2double / ardupilot-mega

Automatically exported from code.google.com/p/ardupilot-mega
0 stars 0 forks source link

Use APM_BinComm for GCS_PROTOCOL_STANDARD #162

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
I've patched APM_BinComm so that it is functional and have tested that I can 
send/recieve comms on microprocessor/ground station end. I think we should use 
APM_BinComm to implement the GCS_PROTOCOL_STANDARD.

My patched version and a sample ground station interface also using the source 
of APM_BinComm is here: hsl.dynalias.com/git

apmcomm : cmake based cross-platform library for talking to ardupilotmega via 
APM_BinComm and the standard protocol definition.

APM_BinComm: my fork of the current version of APM_BinComm with my suggested 
patches applied.

Original issue reported on code.google.com by james.goppert@gmail.com on 1 Oct 2010 at 5:15

GoogleCodeExporter commented 8 years ago

Original comment by dewei...@gmail.com on 25 Oct 2010 at 5:01

GoogleCodeExporter commented 8 years ago

Original comment by DrZip...@gmail.com on 25 Oct 2010 at 5:01

GoogleCodeExporter commented 8 years ago
Issue 204 has been merged into this issue.

Original comment by DrZip...@gmail.com on 25 Oct 2010 at 5:27

GoogleCodeExporter commented 8 years ago
I've attached the patch to fix this issue. It allows us to choose 
GCS_PROTOCOL_BINCOMM. This coupled with the ardupilotcomm library 
http://code.google.com/p/ardupilotmegacomm/ will make it so all that we have to 
do to add new functionality is add a new protocol to protocol.def and 
regenerate. The ground station using the ardupilotmegacomm and the 
microprocessor will then instantly know how to the handle the commands without 
any new coding. I think this would be a very nice capability. If 
GPS_PROTOCOL_BINCOMM is not selected I've wrapped everything so that there 
should be no overhead on the other protocols.

Index: ArduPilotMega/config.h
===================================================================
--- ArduPilotMega/config.h  (revision 1316)
+++ ArduPilotMega/config.h  (working copy)
@@ -97,6 +97,15 @@
 # define DEBUGTERMINAL_VERBOSE 1   //Set this to 1 to get more detail in DEBUGTERMINAL messages, or 0 to save flash space
 #endif

+#if GCS_PORT == 0
+# define GCS_SERIAL Serial
+#elif GCS_PORT == 1
+# define GCS_SERIAL Serial1
+#elif GCS_PORT == 2
+# define GCS_SERIAL Serial2
+#elif GCS_PORT == 3
+# define GCS_SERIAL Serial3
+#endif

 //////////////////////////////////////////////////////////////////////////////
 // Serial port speeds.
Index: ArduPilotMega/GCS_Standard.pde
===================================================================
--- ArduPilotMega/GCS_Standard.pde  (revision 1316)
+++ ArduPilotMega/GCS_Standard.pde  (working copy)
@@ -257,6 +257,16 @@
            mess_buffer[4 + 2 * i] = (tempint >> 8) & 0xff;
        }
        break;
+
+       case MSG_SERVOS:                            // Servos message
+       mess_buffer[0] = 0x10;
+       ck = 16;
+       for(int i = 0; i < 8; i++) {    
+           tempint = servo_out[i];                 // max values
+           mess_buffer[3 + 2 * i] = tempint & 0xff;
+           mess_buffer[4 + 2 * i] = (tempint >> 8) & 0xff;
+       }
+       break;

        case MSG_PID:                               // PID Gains message
        mess_buffer[0]  = 0x0f;
Index: ArduPilotMega/defines.h
===================================================================
--- ArduPilotMega/defines.h (revision 1316)
+++ ArduPilotMega/defines.h (working copy)
@@ -52,6 +52,7 @@
 #define GCS_PROTOCOL_IMU       4   // ArdiPilot IMU output
 #define GCS_PROTOCOL_JASON     5   // Jason's special secret GCS protocol
 #define GCS_PROTOCOL_DEBUGTERMINAL 6   //Human-readable debug interface for use with a dumb terminal
+#define GCS_PROTOCOL_BINCOMM    7   // APMBinComm library implementation of 
standard binary protocol
 #define GCS_PROTOCOL_NONE      -1  // No GCS output

 // PID enumeration
@@ -154,7 +155,7 @@
 #define MSG_TRIMS 0x50
 #define MSG_MINS 0x51
 #define MSG_MAXS 0x52
-#define MSG_IMU_OUT 0x53
+#define MSG_SERVOS 0x53

 #define SEVERITY_LOW 1
 #define SEVERITY_MEDIUM 2
Index: ArduPilotMega/ArduPilotMega.pde
===================================================================
--- ArduPilotMega/ArduPilotMega.pde (revision 1316)
+++ ArduPilotMega/ArduPilotMega.pde (working copy)
@@ -24,6 +24,10 @@
 #include <DataFlash.h>     // ArduPilot Mega Flash Memory Library
 #include <APM_Compass.h>   // ArduPilot Mega Magnetometer Library

+#if (GCS_PROTOCOL == GCS_PROTOCOL_BINCOMM)
+#include <APM_BinComm.h>   // Ardupilot Mega Binary Protocol Library
+#endif
+
 // AVR runtime
 #include <avr/io.h>
 #include <avr/eeprom.h>
@@ -68,6 +72,14 @@
 # error Must select GPS_PROTOCOL_IMU when configuring for X-Plane
 #endif

+#if (GCS_PROTOCOL == GCS_PROTOCOL_BINCOMM)
+   BinComm::MessageHandler handlers[] = {
+       {BinComm::MSG_ANY, handler, NULL},
+       {BinComm::MSG_NULL, 0, 0}
+   };
+   BinComm binComm(handlers,&GCS_SERIAL);
+#endif
+
 // GENERAL VARIABLE DECLARATIONS
 // --------------------------------------------
 byte   control_mode        = MANUAL;
@@ -508,7 +519,15 @@
    set_servos_4();

 #if ENABLE_HIL
+
+   #if GCS_PROTOCOL == GCS_PROTOCOL_BINCOMM
+   send_message(MSG_SERVOS);
+
+   #else
    output_HIL();
+
+   #endif
+
 #endif

 #if GCS_PROTOCOL == GCS_PROTOCOL_DEBUGTERMINAL
@@ -550,11 +569,15 @@
            navigate();
            break;

-       // unused
+       // Look for commands
        //------------------------------
        case 2:
            medium_loopCounter++;

+           #if GCS_PROTOCOL == GCS_PROTOCOL_BINCOMM
+               binComm.update();
+           #endif 
+
            // perform next command
            // --------------------
            update_commands();
Index: ArduPilotMega/GCS_BinComm.pde
===================================================================
--- ArduPilotMega/GCS_BinComm.pde   (revision 0)
+++ ArduPilotMega/GCS_BinComm.pde   (revision 0)
@@ -0,0 +1,55 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
+
+#if GCS_PROTOCOL == GCS_PROTOCOL_BINCOMM
+  
+// receive attitude
+void handler(void * arg, uint8_t id, uint8_t messageVersion, void * 
messageData)
+{
+   switch(id) {
+
+       case MSG_ATTITUDE:
+           int16_t roll,pitch,yaw;
+           binComm.unpack_msg_attitude(roll,pitch,yaw);
+           break;
+   }
+}
+
+void acknowledge(byte id, byte check1, byte check2)
+{
+   binComm.send_msg_acknowledge(id, (check2 << 8) | check1);  // TODO: check 
byte order
+}
+
+void send_message(byte id) 
+{
+   switch(id) {
+    
+       case MSG_HEARTBEAT: // ** System Status message
+       binComm.send_msg_heartbeat(control_mode,millis()/1000,battery_voltage1,comman
d_must_index);
+       break;
+       
+       case MSG_ATTITUDE: // ** Attitude message
+       binComm.send_msg_attitude(roll_sensor,pitch_sensor,yaw_sensor);
+       break;
+       
+       case MSG_LOCATION: // ** Location / GPS message
+       binComm.send_msg_location(current_loc.lat,current_loc.lng,GPS.altitude/100,GP
S.ground_speed,yaw_sensor,GPS.time);
+       break;
+       
+       case MSG_PRESSURE: // ** Pressure message
+       binComm.send_msg_pressure(current_loc.alt/10,(int)airspeed/100);
+       break;
+       
+       case MSG_SERVOS: // ** Servo positions
+       binComm.send_msg_servos(servo_out[0],servo_out[1],servo_out[2],servo_out[3],
+         servo_out[4],servo_out[5],servo_out[6],servo_out[7]);
+       break;
+   }
+}
+
+void send_message(byte id, long param) {}
+void send_message(byte severity, const char *str) {}
+void print_current_waypoints(){}
+void print_waypoint(struct Location *cmd, byte index){}
+void print_waypoints(){}
+
+#endif
Index: ArduPilotMega/APM_Config_bincomm.h
===================================================================
--- ArduPilotMega/APM_Config_bincomm.h  (revision 0)
+++ ArduPilotMega/APM_Config_bincomm.h  (revision 0)
@@ -0,0 +1,19 @@
+#define DEBUG_SUBSYSTEM     0
+
+#define FLIGHT_MODE_CHANNEL    8
+#define FLIGHT_MODE_1      AUTO
+#define FLIGHT_MODE_2      RTL
+#define FLIGHT_MODE_3      FLY_BY_WIRE_A
+#define FLIGHT_MODE_4       FLY_BY_WIRE_B
+#define FLIGHT_MODE_5       STABILIZE
+#define FLIGHT_MODE_6       MANUAL
+
+#define GCS_PROTOCOL        GCS_PROTOCOL_BINCOMM
+#define ENABLE_HIL         ENABLED
+#define GCS_PORT            0
+#define GPS_PROTOCOL       GPS_PROTOCOL_IMU
+#define AIRSPEED_CRUISE     25
+
+#define THROTTLE_FAILSAFE   ENABLED
+#define AIRSPEED_SENSOR        ENABLED
+

Original comment by james.goppert@gmail.com on 28 Oct 2010 at 3:47

GoogleCodeExporter commented 8 years ago
GCS_PROTOCOL_STANDARD is no longer supported in 2.0

Original comment by dewei...@gmail.com on 15 Mar 2011 at 5:13